diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 45de84bd5..bcf05016c 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -2,7 +2,7 @@ Our software is open source so you can solve your own problems without needing help from others. And if you solve a problem and are so kind, you can upstream it for the rest of the world to use. -Most open source development activity is coordinated through our [GitHub Discussions](https://github.com/commaai/openpilot/discussions) and [Discord](https://discord.comma.ai). A lot of documentation is available on our [medium](https://medium.com/@comma_ai/). +Most open source development activity is coordinated through our [GitHub Discussions](https://github.com/commaai/openpilot/discussions) and [Discord](https://discord.comma.ai). A lot of documentation is available on our [blog](https://blog.comma.ai/). ## Getting Started @@ -22,9 +22,9 @@ Code is automatically checked for style by GitHub Actions as part of the automat ## Car Ports (openpilot) -We've released a [Model Port guide](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) for porting to Toyota/Lexus models. +We've released a [Model Port guide](https://blog.comma.ai/openpilot-port-guide-for-toyota-models/) for porting to Toyota/Lexus models. -If you port openpilot to a substantially new car brand, see this more generic [Brand Port guide](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84). +If you port openpilot to a substantially new car brand, see this more generic [Brand Port guide](https://blog.comma.ai/how-to-write-a-car-port-for-openpilot/). ## Pull Requests @@ -36,7 +36,7 @@ Or alternatively, when on the master branch: ``` git submodule update --init ``` -The reasons for having submodules on a dedicated repository and our new development philosophy can be found in our [post about externalization](https://medium.com/@comma_ai/a-2020-theme-externalization-13b33326d8b3). +The reasons for having submodules on a dedicated repository and our new development philosophy can be found in our [post about externalization](https://blog.comma.ai/a-2020-theme-externalization/). Modules that are in seperate repositories include: * cereal * laika diff --git a/Jenkinsfile b/Jenkinsfile index 778d8f3e5..dbcc11066 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -7,6 +7,7 @@ set -e export CI=1 export TEST_DIR=${env.TEST_DIR} +export SOURCE_DIR=${env.SOURCE_DIR} export GIT_BRANCH=${env.GIT_BRANCH} export GIT_COMMIT=${env.GIT_COMMIT} @@ -50,6 +51,7 @@ pipeline { environment { COMMA_JWT = credentials('athena-test-jwt') TEST_DIR = "/data/openpilot" + SOURCE_DIR = "/data/openpilot_source/" } options { timeout(time: 3, unit: 'HOURS') @@ -127,7 +129,8 @@ pipeline { stage('Devel Tests') { steps { phone_steps("eon-build", [ - ["build devel", "cd release && DEVEL_TEST=1 ./build_devel.sh"], + ["build devel", "cd $SOURCE_DIR/release && EXTRA_FILES='tools/' ./build_devel.sh"], + ["build openpilot", "cd selfdrive/manager && ./build.py"], ["test manager", "python selfdrive/manager/test/test_manager.py"], ["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"], ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], @@ -180,21 +183,29 @@ pipeline { } */ - stage('Tici Build') { + stage('tici Build') { environment { R3_PUSH = "${env.BRANCH_NAME == 'master' ? '1' : ' '}" } steps { phone_steps("tici", [ ["build", "cd selfdrive/manager && ./build.py"], - ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], - ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], ["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"], //["build release3-staging", "cd release && PUSH=${env.R3_PUSH} ./build_release3.sh"], ]) } } + stage('Unit Tests (tici)') { + steps { + phone_steps("tici2", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], + ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], + ]) + } + } + stage('camerad') { steps { phone_steps("eon-party", [ @@ -224,7 +235,7 @@ pipeline { } steps { phone_steps("eon-build", [ - ["push devel", "cd release && CI_PUSH='master-ci' ./build_devel.sh"], + ["push devel", "cd $SOURCE_DIR/release && PUSH='master-ci' ./build_devel.sh"], ]) } } diff --git a/README.md b/README.md index e620273dc..ff1cde33e 100644 --- a/README.md +++ b/README.md @@ -57,7 +57,7 @@ openpilot should preserve all other vehicle's stock features, including, but are Supported Hardware ------ -At the moment, openpilot supports the [EON DevKit](https://comma.ai/shop/products/eon-dashcam-devkit) and the [comma two](https://comma.ai/shop/products/comma-two-devkit). A [car harness](https://comma.ai/shop/products/car-harness) is recommended to connect the EON or comma two to the car. For experimental purposes, openpilot can also run on an Ubuntu computer with external [webcams](https://github.com/commaai/openpilot/tree/master/tools/webcam). +At the moment, openpilot supports the EON Gold DevKit and the [comma two](https://comma.ai/shop/products/comma-two-devkit). A [car harness](https://comma.ai/shop/products/car-harness) is recommended to connect the EON or comma two to the car. For experimental purposes, openpilot can also run on an Ubuntu computer with external [webcams](https://github.com/commaai/openpilot/tree/master/tools/webcam). Supported Cars ------ @@ -70,10 +70,12 @@ Supported Cars | Honda | Accord 2018-20 | All | Stock | 0mph | 3mph | | Honda | Accord Hybrid 2018-20 | All | Stock | 0mph | 3mph | | Honda | Civic Hatchback 2017-21 | Honda Sensing | Stock | 0mph | 12mph | -| Honda | Civic Sedan/Coupe 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | -| Honda | Civic Sedan/Coupe 2019-20 | All | Stock | 0mph | 2mph2 | +| Honda | Civic Coupe 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | +| Honda | Civic Coupe 2019-20 | All | Stock | 0mph | 2mph2 | +| Honda | Civic Sedan 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | +| Honda | Civic Sedan 2019-20 | All | Stock | 0mph | 2mph2 | | Honda | CR-V 2015-16 | Touring | openpilot | 25mph1 | 12mph | -| Honda | CR-V 2017-20 | Honda Sensing | Stock | 0mph | 12mph | +| Honda | CR-V 2017-21 | Honda Sensing | Stock | 0mph | 12mph | | Honda | CR-V Hybrid 2017-2019 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Fit 2018-19 | Honda Sensing | openpilot | 25mph1 | 12mph | | Honda | HR-V 2019-20 | Honda Sensing | openpilot | 25mph1 | 12mph | @@ -92,16 +94,17 @@ Supported Cars | Lexus | IS 2017-2019 | All | Stock | 22mph | 0mph | | Lexus | NX 2018 | All | Stock3| 0mph | 0mph | | Lexus | NX 2020 | All | openpilot | 0mph | 0mph | -| Lexus | NX Hybrid 2018 | All | Stock3| 0mph | 0mph | +| Lexus | NX Hybrid 2018-19 | All | Stock3| 0mph | 0mph | | Lexus | RX 2016-18 | All | Stock3| 0mph | 0mph | | Lexus | RX 2020-21 | All | openpilot | 0mph | 0mph | | Lexus | RX Hybrid 2016-19 | All | Stock3| 0mph | 0mph | -| Lexus | RX Hybrid 2020 | All | openpilot | 0mph | 0mph | -| Lexus | UX Hybrid 2019 | All | openpilot | 0mph | 0mph | +| Lexus | RX Hybrid 2020-21 | All | openpilot | 0mph | 0mph | +| Lexus | UX Hybrid 2019-21 | All | openpilot | 0mph | 0mph | +| Toyota | Alphard 2020 | All | openpilot | 0mph | 0mph | | Toyota | Avalon 2016-21 | TSS-P | Stock3| 20mph1 | 0mph | -| Toyota | Avalon Hybrid 2019 | TSS-P | Stock3| 20mph1 | 0mph | +| Toyota | Avalon Hybrid 2019-21 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Camry 2018-20 | All | Stock | 0mph4 | 0mph | -| Toyota | Camry 2021 | All | openpilot | 0mph | 0mph | +| Toyota | Camry 2021 | All | openpilot | 0mph4 | 0mph | | Toyota | Camry Hybrid 2018-20 | All | Stock | 0mph4 | 0mph | | Toyota | Camry Hybrid 2021 | All | openpilot | 0mph | 0mph | | Toyota | C-HR 2017-20 | All | Stock | 0mph | 0mph | @@ -151,19 +154,23 @@ Community Maintained Cars and Features | Genesis | G90 2018 | All | Stock | 0mph | 0mph | | GMC | Acadia 20181 | Adaptive Cruise | openpilot | 0mph | 7mph | | Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Hyundai | Elantra 2017-19, 2021 | SCC + LKAS | Stock | 19mph | 34mph | +| Hyundai | Elantra 2017-19 | SCC + LKAS | Stock | 19mph | 34mph | +| Hyundai | Elantra 2021 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Elantra Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | | Hyundai | Ioniq Electric 2019 | SCC + LKAS | Stock | 0mph | 32mph | | Hyundai | Ioniq Electric 2020 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Ioniq PHEV 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019-20 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2018-2019 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Veloster 2019 | SCC + LKAS | Stock | 5mph | 0mph | +| Hyundai | Veloster 2019-20 | SCC + LKAS | Stock | 5mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-2021 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Niro EV 2020 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Niro PHEV 2019 | SCC + LKAS | Stock | 10mph | 32mph | | Kia | Optima 2017 | SCC + LKAS | Stock | 0mph | 32mph | | Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Seltos 2021 | SCC + LKAS | Stock | 0mph | 0mph | @@ -178,6 +185,7 @@ Community Maintained Cars and Features | SEAT | Leon 2014-2020 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Kodiaq 2018 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Octavia 2015, 2019 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Octavia RS 2016 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Superb 2015-18 | Driver Assistance | Stock | 0mph | 0mph | | Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | @@ -192,10 +200,12 @@ Community Maintained Cars and Features | Volkswagen| Golf GTI 2018-19 | Driver Assistance | Stock | 0mph | 0mph | | Volkswagen| Golf R 2016-19 | Driver Assistance | Stock | 0mph | 0mph | | Volkswagen| Golf SportsVan 2016 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf SportWagen 2015 | Driver Assistance | Stock | 0mph | 0mph | | Volkswagen| Jetta 2018-20 | Driver Assistance | Stock | 0mph | 0mph | | Volkswagen| Jetta GLI 2021 | Driver Assistance | Stock | 0mph | 0mph | | Volkswagen| Passat 2016-172 | Driver Assistance | Stock | 0mph | 0mph | | Volkswagen| Tiguan 2020 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Touran 2017 | Driver Assistance | Stock | 0mph | 0mph | 1Requires an [OBD-II car harness](https://comma.ai/shop/products/comma-car-harness) and [community built ASCM harness](https://github.com/commaai/openpilot/wiki/GM#hardware). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
2Only includes the MQB Passat sold outside of North America. The NMS Passat made in Chattanooga TN is not yet supported. @@ -209,7 +219,7 @@ Although they're not upstream, the community has openpilot running on other make Installation Instructions ------ -Install openpilot on an EON or comma two by entering ``https://openpilot.comma.ai`` during the installer setup. +Install openpilot on an EON Gold or comma two by entering ``https://openpilot.comma.ai`` during the installer setup. Follow these [video instructions](https://youtu.be/lcjqxCymins) to properly mount the device on the windshield. Note: openpilot features an automatic pose calibration routine and openpilot performance should not be affected by small pitch and yaw misalignments caused by imprecise device mounting. @@ -299,7 +309,7 @@ Safety and Testing * panda has software in the loop [safety tests](https://github.com/commaai/panda/tree/master/tests/safety). * Internally, we have a hardware in the loop Jenkins test suite that builds and unit tests the various processes. * panda has additional hardware in the loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). -* We run the latest openpilot in a testing closet containing 10 EONs continuously replaying routes. +* We run the latest openpilot in a testing closet containing 10 comma devices continuously replaying routes. Testing on PC ------ @@ -326,7 +336,7 @@ Community and Contributing openpilot is developed by [comma](https://comma.ai/) and by users like you. We welcome both pull requests and issues on [GitHub](http://github.com/commaai/openpilot). Bug fixes and new car ports are encouraged. -You can add support for your car by following guides we have written for [Brand](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84) and [Model](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) ports. Generally, a car with adaptive cruise control and lane keep assist is a good candidate. [Join our Discord](https://discord.comma.ai) to discuss car ports: most car makes have a dedicated channel. +You can add support for your car by following guides we have written for [Brand](https://blog.comma.ai/how-to-write-a-car-port-for-openpilot/) and [Model](https://blog.comma.ai/openpilot-port-guide-for-toyota-models/) ports. Generally, a car with adaptive cruise control and lane keep assist is a good candidate. [Join our Discord](https://discord.comma.ai) to discuss car ports: most car makes have a dedicated channel. Want to get paid to work on openpilot? [comma is hiring](https://comma.ai/jobs/). @@ -337,27 +347,27 @@ Directory Structure . ├── cereal # The messaging spec and libs used for all logs ├── common # Library like functionality we've developed here - ├── installer/updater # Manages auto-updates of NEOS + ├── installer/updater # Manages updates of NEOS ├── opendbc # Files showing how to interpret data from cars ├── panda # Code used to communicate on CAN - ├── phonelibs # Libraries used on NEOS devices - ├── pyextra # Libraries used on NEOS devices + ├── phonelibs # External libraries + ├── pyextra # Extra python packages not shipped in NEOS └── selfdrive # Code needed to drive the car - ├── assets # Fonts, images and sounds for UI + ├── assets # Fonts, images, and sounds for UI ├── athena # Allows communication with the app ├── boardd # Daemon to talk to the board ├── camerad # Driver to capture images from the camera sensors ├── car # Car specific code to read states and control actuators ├── common # Shared C/C++ code for the daemons - ├── controls # Perception, planning and controls + ├── controls # Planning and controls ├── debug # Tools to help you debug and do car ports - ├── locationd # Soon to be home of precise location + ├── locationd # Precise localization and vehicle parameter estimation ├── logcatd # Android logcat as a service ├── loggerd # Logger and uploader of car data ├── modeld # Driving and monitoring model runners ├── proclogd # Logs information from proc - ├── sensord # IMU / GPS interface code - ├── test # Unit tests, system tests and a car simulator + ├── sensord # IMU interface code + ├── test # Unit tests, system tests, and a car simulator └── ui # The UI Licensing diff --git a/RELEASES.md b/RELEASES.md index 065c4ac5b..767d6331e 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,19 @@ +Version 0.8.6 (2021-07-21) +======================== + * Revamp lateral and longitudinal planners + * Refactor planner output API to be more readable and verbose + * Planners now output desired trajectories for speed, acceleration, curvature, and curvature rate + * Use MPC for longitudinal planning when no lead car is present, makes accel and decel smoother + * Remove "CHECK DRIVER FACE VISIBILITY" warning + * Fixed cruise fault on some TSS2.5 Camrys and international Toyotas + * Hyundai Elantra Hybrid 2021 support thanks to tecandrew! + * Hyundai Ioniq PHEV 2020 support thanks to YawWashout! + * Kia Niro Hybrid 2019 support thanks to jyoung8607! + * Škoda Octavia RS 2016 support thanks to jyoung8607! + * Toyota Alphard 2020 support thanks to belm0! + * Volkswagen Golf SportWagen 2015 support thanks to jona96! + * Volkswagen Touran 2017 support thanks to jyoung8607! + Version 0.8.5 (2021-06-11) ======================== * NEOS update: improved reliability and stability with better voltage regulator configuration diff --git a/SAFETY.md b/SAFETY.md index 9cf8933b9..8b4f33500 100644 --- a/SAFETY.md +++ b/SAFETY.md @@ -28,7 +28,7 @@ ensuring two main safety requirements. react. This means that while the system is engaged, the actuators are constrained to operate within reasonable limits. -For vehicle specific implementation of the safety concept, refer to `panda/board/safety/`. +For additional safety implementation details, refer to [panda safety model](https://github.com/commaai/panda#safety-model). For vehicle specific implementation of the safety concept, refer to [panda/board/safety/](https://github.com/commaai/panda/tree/master/board/safety). **Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or not fully meeting the above requirements. diff --git a/SConstruct b/SConstruct index 6b7905bfc..d5f46f8d9 100644 --- a/SConstruct +++ b/SConstruct @@ -13,6 +13,10 @@ AddOption('--test', action='store_true', help='build test files') +AddOption('--setup', + action='store_true', + help='build setup and installer files') + AddOption('--kaitai', action='store_true', help='Regenerate kaitai struct parsers') @@ -47,6 +51,11 @@ AddOption('--external-sconscript', dest='external_sconscript', help='add an external SConscript to the build') +AddOption('--no-thneed', + action='store_true', + dest='no_thneed', + help='avoid using thneed') + real_arch = arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() if platform.system() == "Darwin": arch = "Darwin" @@ -98,8 +107,8 @@ if arch == "aarch64" or arch == "larch64": "#phonelibs/libyuv/lib", "/system/vendor/lib64" ] - cflags = ["-DQCOM", "-mcpu=cortex-a57"] - cxxflags = ["-DQCOM", "-mcpu=cortex-a57"] + cflags = ["-DQCOM", "-D_USING_LIBCXX", "-mcpu=cortex-a57"] + cxxflags = ["-DQCOM", "-D_USING_LIBCXX", "-mcpu=cortex-a57"] rpath = [] else: cflags = [] @@ -195,8 +204,6 @@ env = Environment( "#phonelibs/qrcode", "#phonelibs", "#cereal", - "#cereal/messaging", - "#cereal/visionipc", "#opendbc/can", ], @@ -317,7 +324,8 @@ qt_flags = [ "-DQT_QUICK_LIB", "-DQT_QUICKWIDGETS_LIB", "-DQT_QML_LIB", - "-DQT_CORE_LIB" + "-DQT_CORE_LIB", + "-DQT_MESSAGELOGCONTEXT", ] qt_env['CXXFLAGS'] += qt_flags qt_env['LIBPATH'] += ['#selfdrive/ui'] @@ -399,8 +407,8 @@ SConscript(['selfdrive/modeld/SConscript']) SConscript(['selfdrive/controls/lib/cluster/SConscript']) SConscript(['selfdrive/controls/lib/lateral_mpc/SConscript']) -SConscript(['selfdrive/controls/lib/longitudinal_mpc/SConscript']) -SConscript(['selfdrive/controls/lib/longitudinal_mpc_model/SConscript']) +SConscript(['selfdrive/controls/lib/lead_mpc_lib/SConscript']) +SConscript(['selfdrive/controls/lib/longitudinal_mpc_lib/SConscript']) SConscript(['selfdrive/boardd/SConscript']) SConscript(['selfdrive/proclogd/SConscript']) diff --git a/cereal/car.capnp b/cereal/car.capnp index 999c064f0..922209433 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -53,7 +53,7 @@ struct CarEvent @0x9b1657f34caf3ad3 { lowSpeedLockout @31; plannerError @32; joystickDebug @34; - steerTempUnavailableUserOverride @35; + steerTempUnavailableSilent @35; resumeRequired @36; preDriverDistracted @37; promptDriverDistracted @38; @@ -78,7 +78,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { stockAeb @64; ldw @65; carUnrecognized @66; - driverMonitorLowAcc @68; invalidLkasSetting @69; speedTooHigh @70; laneChangeBlocked @71; @@ -110,6 +109,7 @@ struct CarEvent @0x9b1657f34caf3ad3 { wideRoadCameraError @102; localizerMalfunction @103; + driverMonitorLowAccDEPRECATED @68; radarCanErrorDEPRECATED @15; radarCommIssueDEPRECATED @67; gasUnavailableDEPRECATED @3; @@ -362,12 +362,11 @@ struct CarParams { fuzzyFingerprint @55 :Bool; enableGasInterceptor @2 :Bool; - enableCruise @3 :Bool; - enableCamera @4 :Bool; - enableDsu @5 :Bool; # driving support unit - enableApgs @6 :Bool; # advanced parking guidance system - enableBsm @56 :Bool; # blind spot monitoring - hasStockCamera @57 :Bool; # factory LKAS/LDW camera is present + pcmCruise @3 :Bool; # is openpilot's state tied to the PCM's cruise state? + enableDsu @5 :Bool; # driving support unit + enableApgs @6 :Bool; # advanced parking guidance system + enableBsm @56 :Bool; # blind spot monitoring + hasStockCamera @57 :Bool; # factory LKAS/LDW camera is present minEnableSpeed @7 :Float32; minSteerSpeed @8 :Float32; @@ -564,5 +563,6 @@ struct CarParams { gateway @1; # Integration at vehicle's CAN gateway } + enableCameraDEPRECATED @4 :Bool; isPandaBlackDEPRECATED @39: Bool; } diff --git a/cereal/log.capnp b/cereal/log.capnp index bd028f511..4f21fcf98 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -123,27 +123,38 @@ struct InitData { struct FrameData { frameId @0 :UInt32; encodeId @1 :UInt32; # DEPRECATED - timestampEof @2 :UInt64; + + frameType @7 :FrameType; frameLength @3 :Int32; + + # Timestamps + timestampEof @2 :UInt64; + timestampSof @8 :UInt64; + + # Exposure integLines @4 :Int32; - globalGain @5 :Int32; + highConversionGain @20 :Bool; + gain @15 :Float32; # This includes highConversionGain if enabled + measuredGreyFraction @21 :Float32; + targetGreyFraction @22 :Float32; + + # Focus lensPos @11 :Int32; lensSag @12 :Float32; lensErr @13 :Float32; lensTruePos @14 :Float32; - image @6 :Data; - gainFrac @15 :Float32; focusVal @16 :List(Int16); focusConf @17 :List(UInt8); sharpnessScore @18 :List(UInt16); recoverState @19 :Int32; - frameType @7 :FrameType; - timestampSof @8 :UInt64; transform @10 :List(Float32); androidCaptureResult @9 :AndroidCaptureResult; + image @6 :Data; + globalGainDEPRECATED @5 :Int32; + enum FrameType { unknown @0; neo @1; @@ -212,6 +223,8 @@ struct SensorEventData { mmc3416x @7; # magnetometer (c2) bmx055 @8; rpr0521 @9; + lsm6ds3trc @10; + mmc5603nj @11; } } @@ -279,6 +292,7 @@ struct DeviceState @0xa4d8b5af2aa492eb { freeSpacePercent @7 :Float32; memoryUsagePercent @19 :Int8; cpuUsagePercent @20 :Int8; + gpuUsagePercent @33 :Int8; usbOnline @12 :Bool; networkType @22 :NetworkType; networkInfo @31 :NetworkInfo; @@ -322,6 +336,7 @@ struct DeviceState @0xa4d8b5af2aa492eb { cell3G @3; cell4G @4; cell5G @5; + ethernet @6; } enum NetworkStrength { @@ -405,7 +420,7 @@ struct PandaState @0xa7649e2575e4591e { registerDivergent @18; interruptRateKlineInit @19; interruptRateClockSource @20; - interruptRateTim9 @21; + interruptRateTick @21; # Update max fault type in boardd when adding faults } @@ -522,7 +537,6 @@ struct ControlsState @0x97ff69c53601abf1 { uiAccelCmd @5 :Float32; ufAccelCmd @33 :Float32; aTarget @35 :Float32; - steeringAngleDesiredDeg @29 :Float32; curvature @37 :Float32; # path curvature from vehicle model forceDecel @51 :Bool; @@ -544,6 +558,7 @@ struct ControlsState @0x97ff69c53601abf1 { pidState @53 :LateralPIDState; lqrState @55 :LateralLQRState; angleState @58 :LateralAngleState; + debugState @59 :LateralDebugState; } enum OpenpilotState @0xdbe58b96d2d1ac61 { @@ -615,6 +630,13 @@ struct ControlsState @0x97ff69c53601abf1 { saturated @3 :Bool; } + struct LateralDebugState { + active @0 :Bool; + steeringAngleDeg @1 :Float32; + output @2 :Float32; + saturated @3 :Bool; + } + # deprecated vEgoDEPRECATED @0 :Float32; vEgoRawDEPRECATED @32 :Float32; @@ -643,6 +665,7 @@ struct ControlsState @0x97ff69c53601abf1 { mapValidDEPRECATED @49 :Bool; jerkFactorDEPRECATED @12 :Float32; steerOverrideDEPRECATED @20 :Bool; + steeringAngleDesiredDegDEPRECATED @29 :Float32; } struct ModelDataV2 { @@ -669,6 +692,7 @@ struct ModelDataV2 { # predicted lead cars leads @11 :List(LeadDataV2); + leadsV3 @18 :List(LeadDataV3); meta @12 :MetaData; @@ -694,6 +718,25 @@ struct ModelDataV2 { xyvaStd @3 :List(Float32); } + struct LeadDataV3 { + prob @0 :Float32; # probability that car is your lead at time t + probTime @1 :Float32; + t @2 :List(Float32); + + # x and y are relative position in device frame + # v absolute norm speed + # a is derivative of v + x @3 :List(Float32); + xStd @4 :List(Float32); + y @5 :List(Float32); + yStd @6 :List(Float32); + v @7 :List(Float32); + vStd @8 :List(Float32); + a @9 :List(Float32); + aStd @10 :List(Float32); + } + + struct MetaData { engagedProb @0 :Float32; desirePrediction @1 :List(Float32); @@ -754,34 +797,35 @@ struct AndroidLogEntry { } struct LongitudinalPlan @0xe00b5b3eba12876c { - mdMonoTime @9 :UInt64; - radarStateMonoTime @10 :UInt64; - - vCruise @16 :Float32; - aCruise @17 :Float32; - vTarget @3 :Float32; - vTargetFuture @14 :Float32; - vMax @20 :Float32; - aTarget @18 :Float32; - - vStart @26 :Float32; - aStart @27 :Float32; - + modelMonoTime @9 :UInt64; hasLead @7 :Bool; fcw @8 :Bool; longitudinalPlanSource @15 :LongitudinalPlanSource; - processingDelay @29 :Float32; + # desired speed/accel/jerk over next 2.5s + accels @32 :List(Float32); + speeds @33 :List(Float32); + jerks @34 :List(Float32); + enum LongitudinalPlanSource { cruise @0; - mpc1 @1; - mpc2 @2; - mpc3 @3; - model @4; + lead0 @1; + lead1 @2; + lead2 @3; + e2e @4; } # deprecated + vCruiseDEPRECATED @16 :Float32; + aCruiseDEPRECATED @17 :Float32; + vTargetDEPRECATED @3 :Float32; + vTargetFutureDEPRECATED @14 :Float32; + aTargetDEPRECATED @18 :Float32; + vStartDEPRECATED @26 :Float32; + aStartDEPRECATED @27 :Float32; + vMaxDEPRECATED @20 :Float32; + radarStateMonoTimeDEPRECATED @10 :UInt64; jerkFactorDEPRECATED @6 :Float32; hasLeftLaneDEPRECATED @23 :Bool; hasRightLaneDEPRECATED @24 :Bool; @@ -819,11 +863,11 @@ struct LateralPlan @0xe1e9318e2ae8b51e { laneChangeState @18 :LaneChangeState; laneChangeDirection @19 :LaneChangeDirection; - # curvature is in rad/m - curvature @22 :Float32; - curvatureRate @23 :Float32; - rawCurvature @24 :Float32; - rawCurvatureRate @25 :Float32; + + # desired curvatures over next 2.5s in rad/m + psis @26 :List(Float32); + curvatures @27 :List(Float32); + curvatureRates @28 :List(Float32); enum Desire { none @0; @@ -849,6 +893,10 @@ struct LateralPlan @0xe1e9318e2ae8b51e { } # deprecated + curvatureDEPRECATED @22 :Float32; + curvatureRateDEPRECATED @23 :Float32; + rawCurvatureDEPRECATED @24 :Float32; + rawCurvatureRateDEPRECATED @25 :Float32; cProbDEPRECATED @3 :Float32; dPolyDEPRECATED @1 :List(Float32); cPolyDEPRECATED @2 :List(Float32); @@ -1201,6 +1249,8 @@ struct DriverState { partialFace @18 :Float32; distractedPose @19 :Float32; distractedEyes @20 :Float32; + eyesOnRoad @21 :Float32; + phoneUse @22 :Float32; irPwrDEPRECATED @10 :Float32; descriptorDEPRECATED @1 :List(Float32); @@ -1301,6 +1351,18 @@ struct ManagerState { } } +struct UploaderState { + immediateQueueSize @0 :UInt32; + immediateQueueCount @1 :UInt32; + rawQueueSize @2 :UInt32; + rawQueueCount @3 :UInt32; + + # stats for last successfully uploaded file + lastTime @4 :Float32; # s + lastSpeed @5 :Float32; # MB/s + lastFilename @6 :Text; +} + struct Event { logMonoTime @0 :UInt64; # nanoseconds valid @67 :Bool = true; @@ -1328,8 +1390,6 @@ struct Event { longitudinalPlan @24 :LongitudinalPlan; lateralPlan @64 :LateralPlan; ubloxGnss @34 :UbloxGnss; - liveMpc @36 :LiveMpcData; - liveLongitudinalMpc @37 :LiveLongitudinalMpcData; ubloxRaw @39 :Data; gpsLocationExternal @48 :GpsLocationData; driverState @59 :DriverState; @@ -1353,6 +1413,7 @@ struct Event { # systems stuff androidLog @20 :AndroidLogEntry; managerState @78 :ManagerState; + uploaderState @79 :UploaderState; procLog @33 :ProcLog; clocks @35 :Clocks; deviceState @6 :DeviceState; @@ -1364,6 +1425,8 @@ struct Event { # *********** legacy + deprecated *********** model @9 :Legacy.ModelData; # TODO: rename modelV2 and mark this as deprecated + liveMpcDEPRECATED @36 :LiveMpcData; + liveLongitudinalMpcDEPRECATED @37 :LiveLongitudinalMpcData; liveLocationKalmanDEPRECATED @51 :Legacy.LiveLocationData; orbslamCorrectionDEPRECATED @45 :Legacy.OrbslamCorrection; liveUIDEPRECATED @14 :Legacy.LiveUI; diff --git a/cereal/messaging/bridge.cc b/cereal/messaging/bridge.cc index da923835a..d4bdfcea7 100644 --- a/cereal/messaging/bridge.cc +++ b/cereal/messaging/bridge.cc @@ -1,59 +1,74 @@ -#include -#include +#include #include #include +#include #include +#include typedef void (*sighandler_t)(int sig); -#include "services.h" - #include "impl_msgq.h" #include "impl_zmq.h" +#include "services.h" void sigpipe_handler(int sig) { assert(sig == SIGPIPE); std::cout << "SIGPIPE received" << std::endl; } -static std::vector get_services() { - std::vector name_list; - +static std::vector get_services(std::string whitelist_str, bool zmq_to_msgq) { + std::vector service_list; for (const auto& it : services) { std::string name = it.name; - if (name == "plusFrame" || name == "uiLayoutState") continue; - name_list.push_back(name); + bool in_whitelist = whitelist_str.find(name) != std::string::npos; + if (name == "plusFrame" || name == "uiLayoutState" || (zmq_to_msgq && !in_whitelist)) { + continue; + } + service_list.push_back(name); } - - return name_list; + return service_list; } - -int main(void){ +int main(int argc, char** argv) { signal(SIGPIPE, (sighandler_t)sigpipe_handler); - auto endpoints = get_services(); + bool zmq_to_msgq = argc > 2; + std::string ip = zmq_to_msgq ? argv[1] : "127.0.0.1"; + std::string whitelist_str = zmq_to_msgq ? std::string(argv[2]) : ""; - std::map sub2pub; - - Context *zmq_context = new ZMQContext(); - Context *msgq_context = new MSGQContext(); - Poller *poller = new MSGQPoller(); - - for (auto endpoint: endpoints){ - SubSocket * msgq_sock = new MSGQSubSocket(); - msgq_sock->connect(msgq_context, endpoint, "127.0.0.1", false); - poller->registerSocket(msgq_sock); - - PubSocket * zmq_sock = new ZMQPubSocket(); - zmq_sock->connect(zmq_context, endpoint); - - sub2pub[msgq_sock] = zmq_sock; + Poller *poller; + Context *pub_context; + Context *sub_context; + if (zmq_to_msgq) { // republishes zmq debugging messages as msgq + poller = new ZMQPoller(); + pub_context = new MSGQContext(); + sub_context = new ZMQContext(); + } else { + poller = new MSGQPoller(); + pub_context = new ZMQContext(); + sub_context = new MSGQContext(); } + std::map sub2pub; + for (auto endpoint: get_services(whitelist_str, zmq_to_msgq)) { + PubSocket * pub_sock; + SubSocket * sub_sock; + if (zmq_to_msgq) { + pub_sock = new MSGQPubSocket(); + sub_sock = new ZMQSubSocket(); + } else { + pub_sock = new ZMQPubSocket(); + sub_sock = new MSGQSubSocket(); + } + pub_sock->connect(pub_context, endpoint); + sub_sock->connect(sub_context, endpoint, ip, false); - while (true){ - for (auto sub_sock : poller->poll(100)){ + poller->registerSocket(sub_sock); + sub2pub[sub_sock] = pub_sock; + } + + while (true) { + for (auto sub_sock : poller->poll(100)) { Message * msg = sub_sock->receive(); if (msg == NULL) continue; sub2pub[sub_sock]->sendMessage(msg); diff --git a/cereal/services.py b/cereal/services.py index bd89cfa31..9acdaefc1 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -19,15 +19,15 @@ class Service: self.frequency = frequency self.decimation = decimation +DCAM_FREQ = 10. if not TICI else 20. services = { - "roadCameraState": (True, 20., 1), # should_log, frequency, decimation (optional) + # service: (should_log, frequency, qlog decimation (optional)) "sensorEvents": (True, 100., 100), "gpsNMEA": (True, 9.), "deviceState": (True, 2., 1), "can": (True, 100.), - "controlsState": (True, 100., 100), - "features": (True, 0.), + "controlsState": (True, 100., 10), "pandaState": (True, 2., 1), "radarState": (True, 20., 5), "roadEncodeIdx": (True, 20., 1), @@ -38,36 +38,29 @@ services = { "androidLog": (True, 0., 1), "carState": (True, 100., 10), "carControl": (True, 100., 10), - "longitudinalPlan": (True, 20., 2), - "liveLocation": (True, 0., 1), + "longitudinalPlan": (True, 20., 5), "procLog": (True, 0.5), "gpsLocationExternal": (True, 10., 1), "ubloxGnss": (True, 10.), "clocks": (True, 1., 1), - "liveMpc": (False, 20.), - "liveLongitudinalMpc": (False, 20.), "ubloxRaw": (True, 20.), "liveLocationKalman": (True, 20., 2), - "uiLayoutState": (True, 0.), "liveParameters": (True, 20., 2), "cameraOdometry": (True, 20., 5), - "lateralPlan": (True, 20., 2), + "lateralPlan": (True, 20., 5), "thumbnail": (True, 0.2, 1), "carEvents": (True, 1., 1), "carParams": (True, 0.02, 1), - "driverCameraState": (True, 10. if not TICI else 20., 1), - "driverEncodeIdx": (True, 10. if not TICI else 20., 1), - "driverState": (True, 10. if not TICI else 20., 1), - "driverMonitoringState": (True, 10. if not TICI else 20., 1), - "offroadLayout": (False, 0.), + "roadCameraState": (True, 20., 20), + "driverCameraState": (True, DCAM_FREQ, DCAM_FREQ), + "driverEncodeIdx": (True, DCAM_FREQ, 1), + "driverState": (True, DCAM_FREQ, DCAM_FREQ / 2), + "driverMonitoringState": (True, DCAM_FREQ, DCAM_FREQ / 2), "wideRoadEncodeIdx": (True, 20., 1), - "wideRoadCameraState": (True, 20., 1), - "modelV2": (True, 20., 20), + "wideRoadCameraState": (True, 20., 20), + "modelV2": (True, 20., 40), "managerState": (True, 2., 1), - - "testModel": (False, 0.), - "testLiveLocation": (False, 0.), - "testJoystick": (False, 0.), + "uploaderState": (True, 0., 1), } service_list = {name: Service(new_port(idx), *vals) for # type: ignore idx, (name, vals) in enumerate(services.items())} diff --git a/cereal/visionipc/visionipc.h b/cereal/visionipc/visionipc.h index 8ecb7da16..fb640692c 100644 --- a/cereal/visionipc/visionipc.h +++ b/cereal/visionipc/visionipc.h @@ -3,7 +3,7 @@ #include #include -constexpr int VISIONIPC_MAX_FDS = 64; +constexpr int VISIONIPC_MAX_FDS = 128; struct VisionIpcBufExtra { uint32_t frame_id; diff --git a/cereal/visionipc/visionipc_client.h b/cereal/visionipc/visionipc_client.h index d2c0085ad..04b2db6b0 100644 --- a/cereal/visionipc/visionipc_client.h +++ b/cereal/visionipc/visionipc_client.h @@ -3,9 +3,9 @@ #include #include -#include "messaging.h" -#include "visionipc.h" -#include "visionbuf.h" +#include "messaging/messaging.h" +#include "visionipc/visionipc.h" +#include "visionipc/visionbuf.h" class VisionIpcClient { private: diff --git a/cereal/visionipc/visionipc_server.cc b/cereal/visionipc/visionipc_server.cc index f4020133d..4aeb40d6e 100644 --- a/cereal/visionipc/visionipc_server.cc +++ b/cereal/visionipc/visionipc_server.cc @@ -7,9 +7,9 @@ #include #include -#include "messaging.h" -#include "ipc.h" -#include "visionipc_server.h" +#include "messaging/messaging.h" +#include "visionipc/ipc.h" +#include "visionipc/visionipc_server.h" std::string get_endpoint_name(std::string name, VisionStreamType type){ if (messaging_use_zmq()){ diff --git a/cereal/visionipc/visionipc_server.h b/cereal/visionipc/visionipc_server.h index 05c517b16..01409f78d 100644 --- a/cereal/visionipc/visionipc_server.h +++ b/cereal/visionipc/visionipc_server.h @@ -5,9 +5,9 @@ #include #include -#include "messaging.h" -#include "visionipc.h" -#include "visionbuf.h" +#include "messaging/messaging.h" +#include "visionipc/visionipc.h" +#include "visionipc/visionbuf.h" std::string get_endpoint_name(std::string name, VisionStreamType type); diff --git a/common/params_pxd.pxd b/common/params_pxd.pxd index 80113c339..489e064dc 100644 --- a/common/params_pxd.pxd +++ b/common/params_pxd.pxd @@ -17,12 +17,12 @@ cdef extern from "selfdrive/common/params.h": ALL cdef cppclass Params: - Params(bool) - Params(string) + Params(bool) nogil + Params(string) nogil string get(string, bool) nogil - bool getBool(string) - int remove(string) - int put(string, string) - int putBool(string, bool) - bool checkKey(string) + bool getBool(string) nogil + int remove(string) nogil + int put(string, string) nogil + int putBool(string, bool) nogil + bool checkKey(string) nogil void clearAll(ParamKeyType) diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index e1ebf95eb..4a238a7d4 100755 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -31,10 +31,14 @@ cdef class Params: cdef c_Params* p def __cinit__(self, d=None, bool persistent_params=False): + cdef string path if d is None: - self.p = new c_Params(persistent_params) + with nogil: + self.p = new c_Params(persistent_params) else: - self.p = new c_Params(d.encode()) + path = d.encode() + with nogil: + self.p = new c_Params(path) def __dealloc__(self): del self.p @@ -53,13 +57,12 @@ cdef class Params: return key - def get(self, key, block=False, encoding=None): + def get(self, key, bool block=False, encoding=None): cdef string k = self.check_key(key) - cdef bool b = block cdef string val with nogil: - val = self.p.get(k, b) + val = self.p.get(k, block) if val == b"": if block: @@ -76,7 +79,10 @@ cdef class Params: def get_bool(self, key): cdef string k = self.check_key(key) - return self.p.getBool(k) + cdef bool r + with nogil: + r = self.p.getBool(k) + return r def put(self, key, dat): """ @@ -86,16 +92,19 @@ cdef class Params: in general try to avoid writing params as much as possible. """ cdef string k = self.check_key(key) - dat = ensure_bytes(dat) - self.p.put(k, dat) + cdef string dat_bytes = ensure_bytes(dat) + with nogil: + self.p.put(k, dat_bytes) - def put_bool(self, key, val): + def put_bool(self, key, bool val): cdef string k = self.check_key(key) - self.p.putBool(k, val) + with nogil: + self.p.putBool(k, val) def delete(self, key): cdef string k = self.check_key(key) - self.p.remove(k) + with nogil: + self.p.remove(k) def put_nonblocking(key, val, d=None): diff --git a/installer/updater/updater.cc b/installer/updater/updater.cc index b2f9dd45b..d1a694ef9 100644 --- a/installer/updater/updater.cc +++ b/installer/updater/updater.cc @@ -557,7 +557,7 @@ struct Updater { // TODO: this should be generic between android versions // IPowerManager.reboot(confirm=false, reason="recovery", wait=true) system("service call power 16 i32 0 s16 recovery i32 1"); - while(1) pause(); + while (true) pause(); // execl("/system/bin/reboot", "recovery"); // set_error("failed to reboot into recovery"); diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 1b71e0730..d76dd9c18 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -84,7 +84,6 @@ function two_init { if [ ! -f "$BASEDIR/prebuilt" ]; then # Clean old build products, but preserve the scons cache cd $DIR - scons --clean git clean -xdf git submodule foreach --recursive git clean -xdf fi @@ -97,68 +96,18 @@ function tici_init { sudo su -c 'echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu0/governor' sudo su -c 'echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu4/governor' nmcli connection modify --temporary lte gsm.auto-config yes + nmcli connection modify --temporary lte gsm.home-only yes # set success flag for current boot slot sudo abctl --set_success # Check if AGNOS update is required if [ $(< /VERSION) != "$AGNOS_VERSION" ]; then - # Get number of slot to switch to - CUR_SLOT=$(abctl --boot_slot) - if [[ "$CUR_SLOT" == "_a" ]]; then - OTHER_SLOT="_b" - OTHER_SLOT_NUMBER="1" - else - OTHER_SLOT="_a" - OTHER_SLOT_NUMBER="0" - fi - echo "Cur slot $CUR_SLOT, target $OTHER_SLOT" - - # Get expected hashes from manifest MANIFEST="$DIR/selfdrive/hardware/tici/agnos.json" - SYSTEM_HASH_EXPECTED=$(jq -r ".[] | select(.name == \"system\") | .hash_raw" $MANIFEST) - SYSTEM_SIZE=$(jq -r ".[] | select(.name == \"system\") | .size" $MANIFEST) - BOOT_HASH_EXPECTED=$(jq -r ".[] | select(.name == \"boot\") | .hash_raw" $MANIFEST) - BOOT_SIZE=$(jq -r ".[] | select(.name == \"boot\") | .size" $MANIFEST) - echo "Expected hashes:" - echo "System: $SYSTEM_HASH_EXPECTED" - echo "Boot: $BOOT_HASH_EXPECTED" + $DIR/selfdrive/hardware/tici/agnos.py --swap $MANIFEST - # Read hashes from alternate partitions, should already be flashed by updated - SYSTEM_HASH=$(dd if="/dev/disk/by-partlabel/system$OTHER_SLOT" bs=1 skip="$SYSTEM_SIZE" count=64 2>/dev/null) - BOOT_HASH=$(dd if="/dev/disk/by-partlabel/boot$OTHER_SLOT" bs=1 skip="$BOOT_SIZE" count=64 2>/dev/null) - echo "Found hashes:" - echo "System: $SYSTEM_HASH" - echo "Boot: $BOOT_HASH" - - if [[ "$SYSTEM_HASH" == "$SYSTEM_HASH_EXPECTED" && "$BOOT_HASH" == "$BOOT_HASH_EXPECTED" ]]; then - echo "Swapping active slot to $OTHER_SLOT_NUMBER" - - # Clean hashes before swapping to prevent looping - dd if=/dev/zero of="/dev/disk/by-partlabel/system$OTHER_SLOT" bs=1 seek="$SYSTEM_SIZE" count=64 - dd if=/dev/zero of="/dev/disk/by-partlabel/boot$OTHER_SLOT" bs=1 seek="$BOOT_SIZE" count=64 - sync - - abctl --set_active "$OTHER_SLOT_NUMBER" - - sleep 1 - sudo reboot - else - echo "Hash mismatch, downloading agnos" - if $DIR/selfdrive/hardware/tici/agnos.py $MANIFEST; then - echo "Download done, swapping active slot to $OTHER_SLOT_NUMBER" - - # Clean hashes before swapping to prevent looping - dd if=/dev/zero of="/dev/disk/by-partlabel/system$OTHER_SLOT" bs=1 seek="$SYSTEM_SIZE" count=64 - dd if=/dev/zero of="/dev/disk/by-partlabel/boot$OTHER_SLOT" bs=1 seek="$BOOT_SIZE" count=64 - sync - - abctl --set_active "$OTHER_SLOT_NUMBER" - fi - - sleep 1 - sudo reboot - fi + sleep 1 + sudo reboot fi } @@ -211,7 +160,7 @@ function launch { # handle pythonpath ln -sfn $(pwd) /data/pythonpath - export PYTHONPATH="$PWD" + export PYTHONPATH="$PWD:$PWD/pyextra" # hardware specific init if [ -f /EON ]; then diff --git a/launch_env.sh b/launch_env.sh index e1ebfbb96..3a3fef74e 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -11,7 +11,7 @@ if [ -z "$REQUIRED_NEOS_VERSION" ]; then fi if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="0.18" + export AGNOS_VERSION="0.21" fi if [ -z "$PASSIVE" ]; then diff --git a/opendbc/acura_ilx_2016_can_generated.dbc b/opendbc/acura_ilx_2016_can_generated.dbc index 361a75cec..7eef23cb3 100644 --- a/opendbc/acura_ilx_2016_can_generated.dbc +++ b/opendbc/acura_ilx_2016_can_generated.dbc @@ -275,7 +275,7 @@ BO_ 316 GAS_PEDAL: 8 PCM BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON diff --git a/opendbc/acura_rdx_2018_can_generated.dbc b/opendbc/acura_rdx_2018_can_generated.dbc index 895e11f00..85600aef3 100644 --- a/opendbc/acura_rdx_2018_can_generated.dbc +++ b/opendbc/acura_rdx_2018_can_generated.dbc @@ -257,7 +257,7 @@ CM_ "acura_rdx_2018_can.dbc starts here"; BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON diff --git a/opendbc/acura_rdx_2020_can_generated.dbc b/opendbc/acura_rdx_2020_can_generated.dbc index ebb51d1db..f9720ce5a 100644 --- a/opendbc/acura_rdx_2020_can_generated.dbc +++ b/opendbc/acura_rdx_2020_can_generated.dbc @@ -69,7 +69,7 @@ BO_ 232 BRAKE_HOLD: 7 XXX BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON diff --git a/opendbc/can/common.cc b/opendbc/can/common.cc index b374467af..0d9d23b5c 100644 --- a/opendbc/can/common.cc +++ b/opendbc/can/common.cc @@ -5,9 +5,11 @@ unsigned int honda_checksum(unsigned int address, uint64_t d, int l) { d >>= 4; // remove checksum int s = 0; + bool extended = address > 0x7FF; // extended can while (address) { s += (address & 0xF); address >>= 4; } while (d) { s += (d & 0xF); d >>= 4; } s = 8-s; + if (extended) s += 3; s &= 0xF; return s; diff --git a/opendbc/honda_accord_2018_can_generated.dbc b/opendbc/honda_accord_2018_can_generated.dbc index fa7f29695..ff286c73d 100644 --- a/opendbc/honda_accord_2018_can_generated.dbc +++ b/opendbc/honda_accord_2018_can_generated.dbc @@ -370,6 +370,48 @@ BO_ 891 STALK_STATUS_2: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; diff --git a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc index ddee5dc16..c2bd5c52e 100644 --- a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc +++ b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc @@ -370,6 +370,48 @@ BO_ 891 STALK_STATUS_2: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; diff --git a/opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc b/opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc index 31e1ddfd7..085ee1de3 100644 --- a/opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc +++ b/opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc @@ -370,6 +370,48 @@ BO_ 891 STALK_STATUS_2: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; diff --git a/opendbc/honda_crv_ex_2017_can_generated.dbc b/opendbc/honda_crv_ex_2017_can_generated.dbc index 8637a426a..2f1c85604 100644 --- a/opendbc/honda_crv_ex_2017_can_generated.dbc +++ b/opendbc/honda_crv_ex_2017_can_generated.dbc @@ -370,6 +370,48 @@ BO_ 891 STALK_STATUS_2: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; diff --git a/opendbc/honda_crv_hybrid_2019_can_generated.dbc b/opendbc/honda_crv_hybrid_2019_can_generated.dbc index 59850d160..99d3a8d1a 100644 --- a/opendbc/honda_crv_hybrid_2019_can_generated.dbc +++ b/opendbc/honda_crv_hybrid_2019_can_generated.dbc @@ -370,6 +370,48 @@ BO_ 891 STALK_STATUS_2: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; diff --git a/opendbc/honda_crv_touring_2016_can_generated.dbc b/opendbc/honda_crv_touring_2016_can_generated.dbc index a3d21d3b8..9486cd082 100644 --- a/opendbc/honda_crv_touring_2016_can_generated.dbc +++ b/opendbc/honda_crv_touring_2016_can_generated.dbc @@ -257,7 +257,7 @@ CM_ "honda_crv_touring_2016_can.dbc starts here"; BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON diff --git a/opendbc/honda_fit_ex_2018_can_generated.dbc b/opendbc/honda_fit_ex_2018_can_generated.dbc index 3f2e2a19d..4b96a01eb 100644 --- a/opendbc/honda_fit_ex_2018_can_generated.dbc +++ b/opendbc/honda_fit_ex_2018_can_generated.dbc @@ -275,7 +275,7 @@ BO_ 304 GAS_PEDAL_2: 8 PCM BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON diff --git a/opendbc/honda_hrv_touring_2019_can_generated.dbc b/opendbc/honda_hrv_touring_2019_can_generated.dbc index 5aea74bc9..4037f9bb3 100644 --- a/opendbc/honda_hrv_touring_2019_can_generated.dbc +++ b/opendbc/honda_hrv_touring_2019_can_generated.dbc @@ -271,7 +271,7 @@ BO_ 316 GAS_PEDAL: 8 PCM BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON diff --git a/opendbc/honda_insight_ex_2019_can_generated.dbc b/opendbc/honda_insight_ex_2019_can_generated.dbc index 59c5735c1..7a511751f 100644 --- a/opendbc/honda_insight_ex_2019_can_generated.dbc +++ b/opendbc/honda_insight_ex_2019_can_generated.dbc @@ -370,6 +370,48 @@ BO_ 891 STALK_STATUS_2: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; diff --git a/opendbc/honda_odyssey_exl_2018_generated.dbc b/opendbc/honda_odyssey_exl_2018_generated.dbc index 7c7526f08..0973233e7 100644 --- a/opendbc/honda_odyssey_exl_2018_generated.dbc +++ b/opendbc/honda_odyssey_exl_2018_generated.dbc @@ -267,7 +267,7 @@ BO_ 316 GAS_PEDAL: 8 PCM BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON diff --git a/opendbc/honda_pilot_touring_2017_can_generated.dbc b/opendbc/honda_pilot_touring_2017_can_generated.dbc index 9cca24912..f037bb8e5 100644 --- a/opendbc/honda_pilot_touring_2017_can_generated.dbc +++ b/opendbc/honda_pilot_touring_2017_can_generated.dbc @@ -275,7 +275,7 @@ BO_ 316 GAS_PEDAL: 8 PCM BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON diff --git a/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc index 0c04d9179..5df1952a0 100644 --- a/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc +++ b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc @@ -270,7 +270,7 @@ BO_ 316 GAS_PEDAL: 8 PCM BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON diff --git a/opendbc/hyundai_kia_generic.dbc b/opendbc/hyundai_kia_generic.dbc index a56ceb708..fd5eb3288 100644 --- a/opendbc/hyundai_kia_generic.dbc +++ b/opendbc/hyundai_kia_generic.dbc @@ -1028,10 +1028,7 @@ BO_ 48 EMS18: 6 EMS BO_ 1322 CLU15: 8 CLU SG_ CF_Clu_VehicleSpeed : 0|8@1+ (1.0,0.0) [0.0|255.0] "" BCM - SG_ CF_Clu_InhibitP : 9|1@1+ (1.0,0.0) [0.0|1.0] "" BCM - SG_ CF_Clu_InhibitR : 10|1@1+ (1.0,0.0) [0.0|1.0] "" BCM - SG_ CF_Clu_InhibitN : 11|1@1+ (1.0,0.0) [0.0|1.0] "" BCM - SG_ CF_Clu_InhibitD : 12|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_Gear : 9|4@1+ (1,0) [0|15] "" BCM SG_ CF_Clu_HudInfoSet : 13|7@1+ (1.0,0.0) [0.0|127.0] "" HUD SG_ CF_Clu_HudFontColorSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" HUD SG_ CF_Clu_HudBrightUpSW : 22|2@1+ (1.0,0.0) [0.0|3.0] "" HUD @@ -1196,7 +1193,7 @@ BO_ 1313 GW_DDM_PE: 8 BCM SG_ C_RRDoorStatus : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU SG_ C_TrunkStatus : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU SG_ C_OSMirrorStatus : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU - + BO_ 1056 SCC11: 8 SCC SG_ MainMode_ACC : 0|1@1+ (1,0) [0|1] "" CLU,EMS,ESC SG_ SCCInfoDisplay : 1|3@1+ (1,0) [0|7] "" CLU,ESC @@ -1523,7 +1520,8 @@ BO_ 881 E_EMS11: 8 XXX SG_ Gear_Change : 12|1@0+ (1,0) [0|31] "" XXX SG_ Cruise_Limit_Status : 13|1@1+ (1,0) [0|1] "" XXX SG_ Cruise_Limit_Target : 23|8@1+ (1,0) [0|15] "" XXX - SG_ Accel_Pedal_Pos : 31|8@1+ (1,0) [0|7] "" XXX + SG_ Accel_Pedal_Pos : 31|8@1+ (1,0) [0|254] "" XXX + SG_ CR_Vcu_AccPedDep_Pos : 56|8@1+ (1,0) [0|254] "" XXX BO_ 1355 EV_PC6: 8 CGW SG_ CF_Vcu_SbwWarnMsg : 16|3@1+ (1,0) [0|7] "" Vector__XXX @@ -1639,8 +1637,14 @@ BO_ 1042 ICM_412h: 8 ICM SG_ PopupMessageOutput_7Level : 54|1@0+ (1,0) [0|1] "" Vector__XXX SG_ PopupMessageOutput_8Level : 55|1@0+ (1,0) [0|1] "" Vector__XXX +VAL_ 274 CUR_GR 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 7 "D" 8 "D" 14 "R" 0 "P"; +VAL_ 871 CF_Lvr_Gear 5 "D" 8 "S" 6 "N" 7 "R" 0 "P"; +VAL_ 882 Elect_Gear_Shifter 5 "D" 8 "S" 6 "N" 7 "R" 0 "P"; +VAL_ 1322 CF_Clu_Gear 1 "P" 2 "R" 4 "N" 8 "D"; VAL_ 909 CF_VSM_Warn 2 "FCW" 3 "AEB"; VAL_ 1157 LFA_Icon_State 0 "no_wheel" 1 "white_wheel" 2 "green_wheel" 3 "green_wheel_blink"; VAL_ 1157 LFA_SysWarning 0 "no_message" 1 "switching_to_hda" 2 "switching_to_scc" 3 "lfa_error" 4 "check_hda" 5 "keep_hands_on_wheel_orange" 6 "keep_hands_on_wheel_red"; VAL_ 1157 HDA_Icon_State 0 "no_hda" 1 "white_hda" 2 "green_hda"; VAL_ 1157 HDA_SysWarning 0 "no_message" 1 "driving_convenience_systems_cancelled" 2 "highway_drive_assist_system_cancelled"; + +CM_ "BO_ E_EMS11: All (plug-in) hybrids use this gas signal: CR_Vcu_AccPedDep_Pos, and all EVs use the Accel_Pedal_Pos signal. See hyundai/values.py for a specific car list"; diff --git a/opendbc/lexus_ct200h_2018_pt_generated.dbc b/opendbc/lexus_ct200h_2018_pt_generated.dbc index 513a9e0a9..676e6169f 100644 --- a/opendbc/lexus_ct200h_2018_pt_generated.dbc +++ b/opendbc/lexus_ct200h_2018_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/lexus_is_2018_pt_generated.dbc b/opendbc/lexus_is_2018_pt_generated.dbc index a1fede6cc..23b6d4ffd 100644 --- a/opendbc/lexus_is_2018_pt_generated.dbc +++ b/opendbc/lexus_is_2018_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/lexus_nx300_2018_pt_generated.dbc b/opendbc/lexus_nx300_2018_pt_generated.dbc index 55ad91963..5940fc33e 100644 --- a/opendbc/lexus_nx300_2018_pt_generated.dbc +++ b/opendbc/lexus_nx300_2018_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/lexus_nx300h_2018_pt_generated.dbc b/opendbc/lexus_nx300h_2018_pt_generated.dbc index 88d3662d8..4c907c135 100644 --- a/opendbc/lexus_nx300h_2018_pt_generated.dbc +++ b/opendbc/lexus_nx300h_2018_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/lexus_rx_350_2016_pt_generated.dbc b/opendbc/lexus_rx_350_2016_pt_generated.dbc index fd0c31d4d..af0554663 100644 --- a/opendbc/lexus_rx_350_2016_pt_generated.dbc +++ b/opendbc/lexus_rx_350_2016_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc index 79100c55e..1b3a33e6a 100644 --- a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc +++ b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/tesla_can.dbc b/opendbc/tesla_can.dbc new file mode 100644 index 000000000..cdc665dc7 --- /dev/null +++ b/opendbc/tesla_can.dbc @@ -0,0 +1,734 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: + NEO + MCU + GTW + EPAS + DI + ESP + SBW + STW + APP + DAS + XXX + +VAL_TABLE_ StW_AnglHP_Spd 16383 "SNA" ; +VAL_TABLE_ DI_aebFaultReason 15 "DI_AEB_FAULT_DAS_REQ_DI_UNAVAIL" 14 "DI_AEB_FAULT_ACCEL_REQ_INVALID" 13 "DI_AEB_FAULT_MIN_TIME_BTWN_EVENTS" 12 "DI_AEB_FAULT_ESP_MIA" 11 "DI_AEB_FAULT_ESP_FAULT" 10 "DI_AEB_FAULT_EPB_NOT_PARKED" 9 "DI_AEB_FAULT_ACCEL_OUT_OF_BOUNDS" 8 "DI_AEB_FAULT_PM_REQUEST" 7 "DI_AEB_FAULT_VEL_EST_ABNORMAL" 6 "DI_AEB_FAULT_DAS_SNA" 5 "DI_AEB_FAULT_DAS_CONTROL_MIA" 4 "DI_AEB_FAULT_SPEED_DELTA" 3 "DI_AEB_FAULT_EBR_FAULT" 2 "DI_AEB_FAULT_PM_MIA" 1 "DI_AEB_FAULT_EPB_MIA" 0 "DI_AEB_FAULT_NONE" ; +VAL_TABLE_ DI_aebLockState 3 "AEB_LOCK_STATE_SNA" 2 "AEB_LOCK_STATE_UNUSED" 1 "AEB_LOCK_STATE_UNLOCKED" 0 "AEB_LOCK_STATE_LOCKED" ; +VAL_TABLE_ DI_aebSmState 7 "DI_AEB_STATE_FAULT" 6 "DI_AEB_STATE_EXIT" 5 "DI_AEB_STATE_STANDSTILL" 4 "DI_AEB_STATE_STOPPING" 3 "DI_AEB_STATE_ENABLE" 2 "DI_AEB_STATE_ENABLE_INIT" 1 "DI_AEB_STATE_STANDBY" 0 "DI_AEB_STATE_UNAVAILABLE" ; +VAL_TABLE_ DI_aebState 7 "AEB_CAN_STATE_SNA" 4 "AEB_CAN_STATE_FAULT" 3 "AEB_CAN_STATE_STANDSTILL" 2 "AEB_CAN_STATE_ENABLED" 1 "AEB_CAN_STATE_STANDBY" 0 "AEB_CAN_STATE_UNAVAILABLE" ; +VAL_TABLE_ DI_epbInterfaceReady 1 "EPB_INTERFACE_READY" 0 "EPB_INTERFACE_NOT_READY" ; +VAL_TABLE_ DI_gear 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ; +VAL_TABLE_ DI_gpoReason 8 "DI_GPO_NUMREASONS" 7 "DI_GPO_CAPACITOR_OVERTEMP" 6 "DI_GPO_NOT_ENOUGH_12V" 5 "DI_GPO_NO_BATTERY_POWER" 4 "DI_GPO_AMBIENT_OVERTEMP" 3 "DI_GPO_FLUID_DELTAT" 2 "DI_GPO_STATOR_OVERTEMP" 1 "DI_GPO_HEATSINK_OVERTEMP" 0 "DI_GPO_OUTLET_OVERTEMP" ; +VAL_TABLE_ DI_immobilizerCondition 1 "DI_IMM_CONDITION_LEARNED" 0 "DI_IMM_CONDITION_VIRGIN_SNA" ; +VAL_TABLE_ DI_immobilizerState 7 "DI_IMM_STATE_FAULT" 6 "DI_IMM_STATE_FAULTRETRY" 5 "DI_IMM_STATE_RESET" 4 "DI_IMM_STATE_LEARN" 3 "DI_IMM_STATE_DISARMED" 2 "DI_IMM_STATE_AUTHENTICATING" 1 "DI_IMM_STATE_REQUEST" 0 "DI_IMM_STATE_INIT_SNA" ; +VAL_TABLE_ DI_limpReason 24 "DI_LIMP_NUMREASONS" 23 "DI_LIMP_CAPACITOR_OVERTEMP" 22 "DI_LIMP_GTW_MIA" 21 "DI_LIMP_TRQCMD_VALIDITY_UNKNOWN" 20 "DI_LIMP_DI_MIA" 19 "DI_LIMP_CONFIG_MISMATCH" 18 "DI_LIMP_HEATSINK_TEMP" 17 "DI_LIMP_PMREQUEST" 16 "DI_LIMP_PMHEARTBEAT" 15 "DI_LIMP_TRQ_CROSS_CHECK" 14 "DI_LIMP_EXTERNAL_COMMAND" 13 "DI_LIMP_WRONG_CS_CALIBRATION" 12 "DI_LIMP_STATOR_TEMP" 11 "DI_LIMP_DELTAT_TOO_NEGATIVE" 10 "DI_LIMP_DELTAT_TOO_POSITIVE" 9 "DI_LIMP_AMBIENT_TEMP" 8 "DI_LIMP_OUTLET_TEMP" 7 "DI_LIMP_LOW_FLOW" 6 "DI_LIMP_BMS_MIA" 5 "DI_LIMP_12V_SUPPLY_UNDERVOLTAGE" 4 "DI_LIMP_NO_FLUID" 3 "DI_LIMP_NO_FUNC_HEATSINK_SENSOR" 2 "DI_LIMP_NO_FUNC_STATORT_SENSOR" 1 "DI_LIMP_BUSV_SENSOR_IRRATIONAL" 0 "DI_LIMP_PHASE_IMBALANCE" ; +VAL_TABLE_ DI_mode 2 "DI_MODE_DYNO" 1 "DI_MODE_DRIVE" 0 "DI_MODE_UNDEF" ; +VAL_TABLE_ DI_motorType 14 "DI_MOTOR_F2AE" 13 "DI_MOTOR_F2AD" 12 "DI_MOTOR_F2AC" 11 "DI_MOTOR_F2AB" 10 "DI_MOTOR_F1AC" 9 "DI_MOTOR_SSR1A" 8 "DI_MOTOR_F1A" 7 "DI_MOTOR_M7M6" 6 "DI_MOTOR_M8A" 5 "DI_MOTOR_M7M5" 4 "DI_MOTOR_M7M4" 3 "DI_MOTOR_M7M3" 2 "DI_MOTOR_ROADSTER_SPORT" 1 "DI_MOTOR_ROADSTER_BASE" 0 "DI_MOTOR_SNA" ; +VAL_TABLE_ DI_speedUnits 1 "DI_SPEED_KPH" 0 "DI_SPEED_MPH" ; +VAL_TABLE_ DI_state 4 "DI_STATE_ENABLE" 3 "DI_STATE_FAULT" 2 "DI_STATE_CLEAR_FAULT" 1 "DI_STATE_STANDBY" 0 "DI_STATE_PREAUTH" ; +VAL_TABLE_ DI_velocityEstimatorState 4 "VE_STATE_BACKUP_MOTOR" 3 "VE_STATE_BACKUP_WHEELS_B" 2 "VE_STATE_BACKUP_WHEELS_A" 1 "VE_STATE_WHEELS_NORMAL" 0 "VE_STATE_NOT_INITIALIZED" ; + + +BO_ 1160 DAS_steeringControl: 4 NEO + SG_ DAS_steeringControlType : 23|2@0+ (1,0) [0|0] "" EPAS + SG_ DAS_steeringControlChecksum : 31|8@0+ (1,0) [0|0] "" EPAS + SG_ DAS_steeringControlCounter : 19|4@0+ (1,0) [0|0] "" EPAS + SG_ DAS_steeringAngleRequest : 6|15@0+ (0.1,-1638.35) [-1638.35|1638.35] "deg" EPAS + SG_ DAS_steeringHapticRequest : 7|1@0+ (1,0) [0|0] "" EPAS + +BO_ 257 GTW_epasControl: 3 NEO + SG_ GTW_epasControlChecksum : 23|8@0+ (1,0) [0|255] "" NEO + SG_ GTW_epasControlCounter : 11|4@0+ (1,0) [0|15] "" NEO + SG_ GTW_epasControlType : 15|2@0+ (1,0) [-1|4] "" NEO + SG_ GTW_epasEmergencyOn : 7|1@0+ (1,0) [-1|2] "" NEO + SG_ GTW_epasLDWEnabled : 12|1@0+ (1,0) [-1|2] "" NEO + SG_ GTW_epasPowerMode : 6|4@0+ (1,0) [4|14] "" NEO + SG_ GTW_epasTuneRequest : 2|3@0+ (1,0) [-1|8] "" NEO + +BO_ 880 EPAS_sysStatus: 8 EPAS + SG_ EPAS_currentTuneMode : 7|4@0+ (1,0) [8|15] "" NEO + SG_ EPAS_eacErrorCode : 23|4@0+ (1,0) [-1|16] "" NEO + SG_ EPAS_eacStatus : 55|3@0+ (1,0) [5|7] "" NEO + SG_ EPAS_handsOnLevel : 39|2@0+ (1,0) [-1|4] "" NEO + SG_ EPAS_internalSAS : 37|14@0+ (0.1,-819.200012) [0|0] "deg" NEO + SG_ EPAS_steeringFault : 2|1@0+ (1,0) [-1|2] "" NEO + SG_ EPAS_steeringRackForce : 1|10@0+ (50,-25575) [0|0] "N" NEO + SG_ EPAS_steeringReduced : 3|1@0+ (1,0) [-1|2] "" NEO + SG_ EPAS_sysStatusChecksum : 63|8@0+ (1,0) [0|255] "" NEO + SG_ EPAS_sysStatusCounter : 51|4@0+ (1,0) [0|15] "" NEO + SG_ EPAS_torsionBarTorque : 19|12@0+ (0.01,-20.5) [0|0] "Nm" NEO + +BO_ 3 STW_ANGL_STAT: 8 STW + SG_ StW_Angl : 5|14@0+ (0.5,-2048) [0|0] "deg" NEO + SG_ StW_AnglSpd : 21|14@0+ (0.5,-2048) [0|0] "/s" NEO + SG_ StW_AnglSens_Stat : 33|2@0+ (1,0) [-1|4] "" NEO + SG_ StW_AnglSens_Id : 35|2@0+ (1,0) [3|3] "" NEO + SG_ MC_STW_ANGL_STAT : 55|4@0+ (1,0) [0|15] "" NEO + SG_ CRC_STW_ANGL_STAT : 63|8@0+ (1,0) [0|255] "" NEO + +BO_ 14 STW_ANGLHP_STAT: 8 STW + + SG_ StW_AnglHP : 5|14@0+ (0.1,-819.2) [-819.2|819] "deg" NEO + SG_ StW_AnglHP_Spd : 21|14@0+ (0.5,-4096) [-4096|4095.5] "deg/s" NEO + SG_ StW_AnglHP_Sens_Stat : 33|2@0+ (1,0) [0|0] "" NEO + SG_ StW_AnglHP_Sens_Id : 35|2@0+ (1,0) [0|0] "" NEO + SG_ MC_STW_ANGLHP_STAT : 55|4@0+ (1,0) [0|15] "" NEO + SG_ CRC_STW_ANGLHP_STAT : 63|8@0+ (1,0) [0|0] "" NEO + +BO_ 264 DI_torque1: 8 DI + SG_ DI_torqueDriver : 0|13@1- (0.25,0) [-750|750] "Nm" NEO + SG_ DI_torque1Counter : 13|3@1+ (1,0) [0|0] "" NEO + SG_ DI_torqueMotor : 16|13@1- (0.25,0) [-750|750] "Nm" NEO + SG_ DI_soptState : 29|3@1+ (1,0) [0|0] "" NEO + SG_ DI_motorRPM : 32|16@1- (1,0) [-17000|17000] "RPM" NEO + SG_ DI_pedalPos : 48|8@1+ (0.4,0) [0|100] "%" NEO + SG_ DI_torque1Checksum : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 280 DI_torque2: 6 DI + SG_ DI_torqueEstimate : 0|12@1- (0.5,0) [-750|750] "Nm" NEO + SG_ DI_gear : 12|3@1+ (1,0) [0|0] "" NEO + SG_ DI_brakePedal : 15|1@1+ (1,0) [0|0] "" NEO + SG_ DI_vehicleSpeed : 16|12@1+ (0.05,-25) [-25|179.75] "MPH" NEO + SG_ DI_gearRequest : 28|3@1+ (1,0) [0|0] "" NEO + SG_ DI_torqueInterfaceFailure : 31|1@1+ (1,0) [0|0] "" NEO + SG_ DI_torque2Counter : 32|4@1+ (1,0) [0|0] "" NEO + SG_ DI_brakePedalState : 36|2@1+ (1,0) [0|0] "" NEO + SG_ DI_epbParkRequest : 38|1@1+ (1,0) [0|0] "" NEO + SG_ DI_epbInterfaceReady : 39|1@1+ (1,0) [0|0] "" NEO + SG_ DI_torque2Checksum : 40|8@1+ (1,0) [0|0] "" NEO + +BO_ 309 ESP_135h: 5 ESP + SG_ ESP_135hChecksum : 23|8@0+ (1,0) [0|255] "" NEO + SG_ ESP_135hCounter : 11|4@0+ (1,0) [0|15] "" NEO + SG_ ESP_absBrakeEvent : 2|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_brakeDiscWipingActive : 4|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_brakeLamp : 3|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_espFaultLamp : 6|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_espLampFlash : 7|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_hillStartAssistActive : 1|2@0+ (1,0) [-1|4] "" NEO + SG_ ESP_messagePumpService : 24|1@0+ (1,0) [0|1] "" NEO + SG_ ESP_messagePumpFailure : 25|1@0+ (1,0) [0|1] "" NEO + SG_ ESP_messageEBDFailure : 26|1@0+ (1,0) [0|1] "" NEO + SG_ ESP_absFaultLamp : 27|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_tcDisabledByFault : 28|1@0+ (1,0) [0|1] "" NEO + SG_ ESP_messageDynoModeActive : 29|1@0+ (1,0) [0|1] "" NEO + SG_ ESP_hydraulicBoostEnabled : 30|1@0+ (1,0) [0|1] "" NEO + SG_ ESP_espOffLamp : 31|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_stabilityControlSts : 14|3@0+ (1,0) [6|7] "" NEO + SG_ ESP_tcLampFlash : 5|1@0+ (1,0) [-1|2] "" NEO + SG_ ESP_tcOffLamp : 15|1@0+ (1,0) [0|1] "" NEO + +BO_ 341 ESP_B: 8 ESP + SG_ ESP_BChecksum : 39|8@0+ (1,0) [0|255] "" NEO,EPAS + SG_ ESP_BCounter : 62|4@0+ (1,0) [1|15] "" NEO,EPAS + SG_ ESP_vehicleSpeed : 47|16@0+ (0.00999999978,0) [0|0] "kph" NEO,EPAS + SG_ ESP_vehicleSpeedQF : 57|2@0+ (1,0) [1|2] "" NEO,EPAS + SG_ ESP_wheelPulseCountFrL : 7|8@0+ (1,0) [0|254] "" NEO,EPAS + SG_ ESP_wheelPulseCountFrR : 15|8@0+ (1,0) [0|254] "" NEO,EPAS + SG_ ESP_wheelPulseCountReL : 23|8@0+ (1,0) [0|254] "" NEO,EPAS + SG_ ESP_wheelPulseCountReR : 31|8@0+ (1,0) [0|254] "" NEO,EPAS + +BO_ 513 SDM1: 5 GTW + SG_ SDM_bcklPassStatus : 3|2@0+ (1,0) [0|3] "" NEO + SG_ SDM_bcklDrivStatus : 5|2@0+ (1,0) [0|3] "" NEO + +BO_ 532 EPB_epasControl: 3 EPB + SG_ EPB_epasControlChecksum : 23|8@0+ (1,0) [0|255] "" NEO,EPAS + SG_ EPB_epasControlCounter : 11|4@0+ (1,0) [0|15] "" NEO,EPAS + SG_ EPB_epasEACAllow : 2|3@0+ (1,0) [4|7] "" NEO,EPAS + +BO_ 792 GTW_carState: 8 GTW + SG_ YEAR : 0|7@1+ (1,2000) [2000|2127] "Year" NEO + SG_ CERRD : 7|1@1+ (1,0) [0|1] "" NEO + SG_ MONTH : 8|4@1+ (1,0) [1|12] "Month" NEO + SG_ DOOR_STATE_FL : 12|2@1+ (1,0) [0|3] "" NEO + SG_ DOOR_STATE_FR : 14|2@1+ (1,0) [0|3] "" NEO + SG_ SECOND : 16|6@1+ (1,0) [0|59] "s" NEO + SG_ DOOR_STATE_RL : 22|2@1+ (1,0) [0|3] "" NEO + SG_ Hour : 24|5@1+ (1,0) [0|23] "h" NEO + SG_ DOOR_STATE_RR : 29|2@1+ (1,0) [0|3] "" NEO + SG_ DAY : 32|5@1+ (1,0) [0|31] "" NEO + SG_ MINUTE : 40|6@1+ (1,0) [0|59] "min" NEO + SG_ BOOT_STATE : 46|2@1+ (1,0) [0|3] "" NEO + SG_ GTW_updateInProgress : 48|2@1+ (1,0) [0|3] "" NEO + SG_ DOOR_STATE_FrontTrunk : 50|2@1+ (1,0) [0|3] "" NEO + SG_ MCU_factoryMode : 52|1@1+ (1,0) [0|1] "" NEO + SG_ MCU_transportModeOn : 53|1@0+ (1,0) [0|1] "" NEO + SG_ BC_headLightLStatus : 55|2@0+ (1,0) [0|3] "" NEO + SG_ BC_headLightRStatus : 57|2@0+ (1,0) [0|3] "" NEO + SG_ BC_indicatorLStatus : 59|2@0+ (1,0) [0|3] "" NEO + SG_ BC_indicatorRStatus : 61|2@0+ (1,0) [0|3] "" NEO + +BO_ 872 DI_state: 8 DI + SG_ DI_systemState : 0|3@1+ (1,0) [0|0] "" NEO + SG_ DI_vehicleHoldState : 3|3@1+ (1,0) [0|0] "" NEO + SG_ DI_proximity : 6|1@1+ (1,0) [0|0] "" NEO + SG_ DI_driveReady : 7|1@1+ (1,0) [0|0] "" NEO + SG_ DI_regenLight : 8|1@1+ (1,0) [0|0] "" NEO + SG_ DI_state : 9|3@1+ (1,0) [0|0] "" NEO + SG_ DI_cruiseState : 12|4@1+ (1,0) [0|0] "" NEO + SG_ DI_analogSpeed : 16|12@1+ (0.1,0) [0|150] "speed" NEO + SG_ DI_immobilizerState : 28|3@1+ (1,0) [0|0] "" NEO + SG_ DI_speedUnits : 31|1@1+ (1,0) [0|1] "" NEO + SG_ DI_cruiseSet : 32|9@1+ (0.5,0) [0|255.5] "speed" NEO + SG_ DI_aebState : 41|3@1+ (1,0) [0|0] "" NEO + SG_ DI_stateCounter : 44|4@1+ (1,0) [0|0] "" NEO + SG_ DI_digitalSpeed : 48|8@1+ (1,0) [0|250] "" NEO + SG_ DI_stateChecksum : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 109 SBW_RQ_SCCM: 4 STW + SG_ StW_Sw_Stat3 : 0|3@1+ (1,0) [0|0] "" NEO + SG_ MsgTxmtId : 6|2@1+ (1,0) [0|0] "" NEO + SG_ TSL_RND_Posn_StW : 8|4@1+ (1,0) [0|0] "" NEO + SG_ TSL_P_Psd_StW : 12|2@1+ (1,0) [0|0] "" NEO + SG_ MC_SBW_RQ_SCCM : 20|4@1+ (1,0) [0|15] "" NEO + SG_ CRC_SBW_RQ_SCCM : 24|8@1+ (1,0) [0|0] "" NEO + +BO_ 69 STW_ACTN_RQ: 8 STW + SG_ SpdCtrlLvr_Stat : 0|6@1+ (1,0) [0|0] "" NEO + SG_ VSL_Enbl_Rq : 6|1@1+ (1,0) [0|0] "" NEO + SG_ SpdCtrlLvrStat_Inv : 7|1@1+ (1,0) [0|0] "" NEO + SG_ DTR_Dist_Rq : 8|8@1+ (1,0) [0|200] "" NEO + SG_ TurnIndLvr_Stat : 16|2@1+ (1,0) [0|0] "" NEO + SG_ HiBmLvr_Stat : 18|2@1+ (1,0) [0|0] "" NEO + SG_ WprWashSw_Psd : 20|2@1+ (1,0) [0|0] "" NEO + SG_ WprWash_R_Sw_Posn_V2 : 22|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Lvr_Stat : 24|3@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Flt : 27|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Psd : 28|2@1+ (1,0) [0|0] "" NEO + SG_ HrnSw_Psd : 30|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw00_Psd : 32|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw01_Psd : 33|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw02_Psd : 34|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw03_Psd : 35|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw04_Psd : 36|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw05_Psd : 37|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw06_Psd : 38|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw07_Psd : 39|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw08_Psd : 40|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw09_Psd : 41|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw10_Psd : 42|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw11_Psd : 43|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw12_Psd : 44|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw13_Psd : 45|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw14_Psd : 46|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw15_Psd : 47|1@1+ (1,0) [0|0] "" NEO + SG_ WprSw6Posn : 48|3@1+ (1,0) [0|0] "" NEO + SG_ MC_STW_ACTN_RQ : 52|4@1+ (1,0) [0|15] "" NEO + SG_ CRC_STW_ACTN_RQ : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 643 BODY_R1: 8 GTW + SG_ AirTemp_Insd : 47|8@0+ (0.25,0) [0|63.5] "C" NEO + SG_ AirTemp_Outsd : 63|8@0+ (0.5,-40) [-40|86.5] "C" NEO + SG_ Bckl_Sw_RL_Stat_SAM_R : 49|2@0+ (1,0) [-1|4] "" NEO + SG_ Bckl_Sw_RM_Stat_SAM_R : 53|2@0+ (1,0) [-1|4] "" NEO + SG_ Bckl_Sw_RR_Stat_SAM_R : 51|2@0+ (1,0) [-1|4] "" NEO + SG_ DL_RLtch_Stat : 9|2@0+ (1,0) [-1|4] "" NEO + SG_ DrRLtch_FL_Stat : 1|2@0+ (1,0) [-1|4] "" NEO + SG_ DrRLtch_FR_Stat : 3|2@0+ (1,0) [-1|4] "" NEO + SG_ DrRLtch_RL_Stat : 5|2@0+ (1,0) [-1|4] "" NEO + SG_ DrRLtch_RR_Stat : 7|2@0+ (1,0) [-1|4] "" NEO + SG_ EngHd_Stat : 11|2@0+ (1,0) [-1|4] "" NEO + SG_ LoBm_On_Rq : 32|1@0+ (1,0) [0|1] "" NEO + SG_ HiBm_On : 33|1@0+ (1,0) [0|1] "" NEO + SG_ Hrn_On : 26|1@0+ (1,0) [0|1] "" NEO + SG_ IrLmp_D_Lt_Flt : 34|1@0+ (1,0) [0|1] "" NEO + SG_ IrLmp_P_Rt_Flt : 35|1@0+ (1,0) [0|1] "" NEO + SG_ LgtSens_Twlgt : 18|3@0+ (1,0) [0|7] "Steps" NEO + SG_ LgtSens_SNA : 19|1@0+ (1,0) [0|1] "" NEO + SG_ LgtSens_Tunnel : 20|1@0+ (1,0) [0|1] "" NEO + SG_ LgtSens_Flt : 21|1@0+ (1,0) [0|1] "" NEO + SG_ LgtSens_Night : 22|1@0+ (1,0) [-1|2] "" NEO + SG_ ADL_LoBm_On_Rq : 23|1@0+ (1,0) [0|1] "" NEO + SG_ LoBm_D_Lt_Flt : 36|1@0+ (1,0) [0|1] "" NEO + SG_ LoBm_P_Rt_Flt : 37|1@0+ (1,0) [0|1] "" NEO + SG_ MPkBrk_Stat : 28|1@0+ (1,0) [-1|2] "" NEO + SG_ RevGr_Engg : 39|2@0+ (1,0) [-1|4] "" NEO + SG_ StW_Cond_Stat : 55|2@0+ (1,0) [-1|4] "" NEO + SG_ Term54_Actv : 27|1@0+ (1,0) [0|1] "" NEO + SG_ Trlr_Stat : 25|2@0+ (1,0) [-1|4] "" NEO + SG_ VTA_Alm_Actv : 13|1@0+ (1,0) [0|1] "" NEO + SG_ WprOutsdPkPosn : 29|1@0+ (1,0) [0|1] "" NEO + +BO_ 760 UI_gpsVehicleSpeed: 8 GTW + SG_ UI_gpsHDOP : 0|8@1+ (0.1,0) [0|25.5] "1" DAS + SG_ UI_gpsVehicleHeading : 8|16@1+ (0.0078125,0) [0|511.9921875] "deg" DAS + SG_ UI_gpsVehicleSpeed : 24|16@1+ (0.00390625,0) [0|250.996] "km/hr" Vector__XXX + SG_ UI_userSpeedOffset : 40|6@1+ (1,-30) [-30|33] "kph/mph" DAS + SG_ UI_mapSpeedLimitUnits : 46|1@1+ (1,0) [0|1] "" DAS + SG_ UI_userSpeedOffsetUnits : 47|1@1+ (1,0) [0|1] "" DAS + SG_ UI_mppSpeedLimit : 48|5@1+ (5,0) [0|155] "kph/mph" DAS + SG_ UI_gpsNmeaMIA : 53|1@1+ (1,0) [0|0] "" DAS + +BO_ 536 MCU_chassisControl: 8 GTW + SG_ MCU_dasDebugEnable : 0|1@1+ (1,0) [0|0] "" NEO + SG_ MCU_parkBrakeRequest : 1|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_trailerModeCH : 3|1@1+ (1,0) [0|0] "" NEO + SG_ MCU_fcwSensitivity : 4|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_fcwEnable : 6|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_latControlEnable : 8|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_accOvertakeEnable : 10|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_ldwEnable : 12|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_aebEnable : 14|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_bsdEnable : 16|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_ahlbEnable : 18|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_parkSetting : 20|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_pedalSafetyEnable : 22|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_frontDefrostReq_das : 24|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_autoParkRequest : 26|4@1+ (1,0) [0|0] "" NEO + SG_ MCU_redLightStopSignEnable : 30|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_enableCreepTorqueCH : 32|1@1+ (1,0) [0|0] "" NEO + SG_ MCU_narrowGarages : 33|1@1+ (1,0) [0|0] "" NEO + SG_ MCU_rebootAutopilot : 34|1@1+ (1,0) [0|0] "" NEO + SG_ MCU_enableAutowipers : 35|1@1+ (1,0) [0|0] "" NEO + SG_ MCU_overPaintedUSS : 38|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_selfParkTune : 40|4@1+ (1,0) [0|15] "" NEO + SG_ MCU_towModeEnable : 44|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_zeroSpeedConfirmed : 46|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_aesEnable : 48|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_autoLaneChangeEnable : 50|2@1+ (1,0) [0|0] "" NEO + SG_ MCU_chassisControlCounter : 52|4@1+ (1,0) [0|0] "" NEO + SG_ MCU_chassisControlChecksum : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 904 MCU_clusterBacklightRequest: 3 NEO + SG_ MCU_clusterBacklightOn : 7|1@1+ (1,0) [0|1] "" NEO + SG_ MCU_clusterBrightnessLevel : 8|8@1+ (0.5,0) [0|127.5] "%" NEO + SG_ MCU_clusterReadyForDrive : 6|1@1+ (1,0) [-1|2] "" NEO + SG_ MCU_clusterReadyForPowerOff : 5|1@1+ (1,0) [0|1] "" NEO + +BO_ 984 MCU_locationStatus: 8 MCU + SG_ MCU_gpsAccuracy : 57|7@1+ (0.2,0) [0|0] "m" NEO + SG_ MCU_latitude : 0|28@1- (1E-06,0) [0|0] "deg" NEO + SG_ MCU_longitude : 28|29@1- (1E-06,0) [0|0] "deg" NEO + +BO_ 104 MCU_locationStatus2: 8 MCU + SG_ MCU_elevation : 0|32@1- (0.1,0) [0|0] "m" GTW + SG_ MCU_navigonExpectedSpeed : 32|7@1+ (1,0) [0|126] "mph" GTW + +BO_ 840 GTW_status: 8 GTW + SG_ GTW_accGoingDown : 6|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_accRailReq : 8|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_brakePressed : 1|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_driveGoingDown : 7|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_driveRailReq : 0|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_driverIsLeaving : 5|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_driverPresent : 2|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_hvacGoingDown : 11|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_hvacRailReq : 9|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_icPowerOff : 4|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_notEnough12VForDrive : 3|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_preconditionRequest : 10|1@0+ (1,0) [0|1] "" NEO + SG_ GTW_statusChecksum : 63|8@0+ (1,0) [0|255] "" NEO + SG_ GTW_statusCounter : 51|4@0+ (1,0) [0|15] "" NEO + +BO_ 920 GTW_carConfig: 8 GTW + SG_ GTW_performanceConfig : 2|3@0+ (1,0) [0|0] "" NEO + SG_ GTW_fourWheelDrive : 4|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_unknown1 : 5|1@0+ (1,0) [0|0] "" NEO + SG_ GTW_dasHw : 7|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_parkAssistInstalled : 9|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_forwardRadarHw : 11|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_airSuspensionInstalled : 14|3@0+ (1,0) [0|0] "" NEO + SG_ GTW_unknown2 : 15|1@0+ (1,0) [0|0] "" NEO + SG_ GTW_country : 23|16@0+ (1,0) [0|0] "" NEO + SG_ GTW_parkSensorGeometryType : 33|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_rhd : 34|1@0+ (1,0) [0|0] "" NEO + SG_ GTW_bodyControlsType : 35|1@0+ (1,0) [0|0] "" NEO + SG_ GTW_radarPosition : 39|4@0+ (1,0) [0|0] "" NEO + SG_ GTW_rearCornerRadarHw : 41|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_frontCornerRadarHw : 43|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_epasType : 45|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_chassisType : 47|2@0+ (1,0) [0|2] "" NEO + SG_ GTW_wheelType : 52|5@0+ (1,0) [0|0] "" NEO + SG_ GTW_rearSeatControllerMask : 55|3@0+ (1,0) [0|7] "" NEO + SG_ GTW_euVehicle : 56|1@0+ (1,0) [0|0] "" NEO + SG_ GTW_foldingMirrorsInstalled : 57|1@0+ (1,0) [0|0] "" NEO + SG_ GTW_brakeHwType : 59|2@0+ (1,0) [0|2] "" NEO + SG_ GTW_autopilot : 61|2@0+ (1,0) [0|0] "" NEO + SG_ GTW_unknown3 : 63|2@0+ (1,0) [0|0] "" NEO + +BO_ 1006 UI_autopilotControl: 8 GTW + SG_ UI_autopilotControlIndex M : 0|3@1+ (1,0) [0|7] "" APP,APS + SG_ UI_hovEnabled m0 : 3|1@1+ (1,0) [0|0] "" APP,APS + SG_ UI_donDisableAutoWiperDuration m0 : 4|3@1+ (1,0) [0|0] "" APP,APS + SG_ UI_donDisableOnAutoWiperSpeed m0 : 7|4@1+ (1,0) [0|0] "" APP,APS + SG_ UI_blindspotMinSpeed m0 : 11|4@1+ (1,0) [0|0] "" APP,APS + SG_ UI_blindspotDistance m0 : 15|3@1+ (1,0) [0|0] "" APP,APS + SG_ UI_blindspotTTC m0 : 18|3@1+ (1,0) [0|0] "" APP,APS + SG_ UI_donStopEndOfRampBuffer m0 : 21|3@1+ (1,0) [0|0] "" APP,APS + SG_ UI_donDisableCutin m0 : 24|1@1+ (1,0) [0|0] "" APP,APS + SG_ UI_donMinGoreWidthForAbortMap m0 : 25|4@1+ (1,0) [0|0] "" APP,APS + SG_ UI_donAlcProgGoreAbortThres m0 : 29|4@1+ (1,0) [0|0] "" APP,APS + SG_ UI_donMinGoreWidthForAbortNotMap m0 : 33|4@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcDisableUltrasonicCheck m0 : 37|1@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcUltrasonicDistance m0 : 38|4@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcUltrasonicWaitTime m0 : 42|3@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcEgoLeadingReactionAccel m0 : 48|2@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcMergIntervalRearDHyst m0 : 50|2@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcMergingIntervalHeadwayHyst m0 : 52|2@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcAssertivenessRate m0 : 54|2@1+ (1,0) [0|0] "" APP,APS + SG_ UI_alcViewRangeSensitivity m0 : 56|2@1+ (1,0) [0|0] "" APP,APS + SG_ UI_camBlockLaneCheckDisable m1 : 3|1@1+ (1,0) [0|0] "" APP,APS + SG_ UI_camBlockLaneCheckThreshold m1 : 4|6@1+ (0.01587,0) [0|1] "%" APP,APS + SG_ UI_camBlockBlurDisable m1 : 10|1@1+ (1,0) [0|0] "" APP,APS + SG_ UI_camBlockBlurThreshold m1 : 11|6@1+ (0.01587,0) [0|1] "%" APP,APS + +BO_ 728 UI_csaOfframpCurvature: 8 GTW + SG_ UI_csaOfframpCurvC2 : 0|16@1- (1E-06,0) [-0.032768|0.032767] "1/m" DAS + SG_ UI_csaOfframpCurvC3 : 16|16@1- (4E-09,0) [-0.000131072|0.000131068] "1/m2" DAS + SG_ UI_csaOfframpCurvRange : 32|8@1+ (2,0) [0|510] "m" DAS + SG_ UI_csaOfframpCurvCounter : 40|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ UI_csaOfframpCurvUsingTspline : 48|1@1+ (1,0) [0|1] "" DAS + SG_ UI_csaOfframpCurvReserved : 49|7@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_csaOfframpCurvChecksum : 56|8@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 744 UI_csaRoadCurvature: 8 GTW + SG_ UI_csaRoadCurvC2 : 0|16@1- (1E-06,0) [-0.032768|0.032767] "1/m" DAS + SG_ UI_csaRoadCurvC3 : 16|16@1- (4E-09,0) [-0.000131072|0.000131068] "1/m2" DAS + SG_ UI_csaRoadCurvRange : 32|8@1+ (2,0) [0|510] "m" DAS + SG_ UI_csaRoadCurvCounter : 40|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ UI_csaRoadCurvUsingTspline : 48|1@1+ (1,0) [0|1] "" DAS + SG_ UI_csaRoadCurvReserved : 49|7@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_csaRoadCurvChecksum : 56|8@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 1080 UI_driverAssistAnonDebugParams: 8 GTW + SG_ UI_anonDebugParam1 : 0|7@1+ (1,0) [0|100] "" DAS + SG_ UI_anonDebugFlag1 : 7|1@1+ (1,0) [0|0] "" DAS + SG_ UI_anonDebugParam2 : 8|7@1+ (1,0) [0|100] "" DAS + SG_ UI_anonDebugFlag2 : 15|1@1+ (1,0) [0|0] "" DAS + SG_ UI_anonDebugParam3 : 16|7@1+ (1,0) [0|100] "" DAS + SG_ UI_anonDebugFlag3 : 23|1@1+ (1,0) [0|0] "" DAS + SG_ UI_anonDebugParam4 : 24|7@1+ (1,0) [0|100] "" DAS + SG_ UI_anonDebugFlag4 : 31|1@1+ (1,0) [0|0] "" DAS + SG_ UI_anonDebugParam5 : 32|7@1+ (1,0) [0|100] "" DAS + SG_ UI_anonDebugParam6 : 40|7@1+ (1,0) [0|100] "" DAS + SG_ UI_anonDebugParam7 : 48|7@1+ (1,0) [0|100] "" DAS + SG_ UI_visionSpeedSlider : 56|7@1+ (1,0) [0|100] "" DAS + +BO_ 1000 UI_driverAssistControl: 8 GTW + SG_ UI_autopilotControlRequest : 0|1@1+ (1,0) [1|0] "" DAS + SG_ UI_ulcStalkConfirm : 1|1@1+ (1,0) [1|0] "" DAS + SG_ UI_summonHeartbeat : 2|2@1+ (1,0) [0|0] "" DAS + SG_ UI_curvSpeedAdaptDisable : 4|1@1+ (1,0) [0|0] "" DAS + SG_ UI_dasDeveloper : 5|1@1+ (1,0) [0|0] "" DAS + SG_ UI_enableVinAssociation : 6|1@1+ (1,0) [0|0] "" DAS + SG_ UI_lssLkaEnabled : 7|1@1+ (1,0) [0|0] "" DAS + SG_ UI_lssLdwEnabled : 8|1@1+ (1,0) [0|0] "" DAS + SG_ UI_autoSummonEnable : 10|1@1+ (1,0) [0|1] "" DAS + SG_ UI_exceptionListEnable : 11|1@1+ (1,0) [0|1] "" APP + SG_ UI_roadCheckDisable : 12|1@1+ (1,0) [0|0] "" DAS + SG_ UI_driveOnMapsEnable : 13|1@1+ (1,0) [0|0] "" DAS + SG_ UI_handsOnRequirementDisable : 14|1@1+ (1,0) [0|0] "" DAS + SG_ UI_forksEnable : 15|1@1+ (1,0) [0|0] "" DAS + SG_ UI_fuseLanesDisable : 16|1@1+ (1,0) [0|0] "" DAS + SG_ UI_fuseHPPDisable : 17|1@1+ (1,0) [0|0] "" DAS + SG_ UI_fuseVehiclesDisable : 18|1@1+ (1,0) [0|0] "" DAS + SG_ UI_enableNextGenACC : 19|1@1+ (1,0) [0|1] "" APP + SG_ UI_visionSpeedType : 20|2@1+ (1,0) [0|0] "" APP + SG_ UI_curvatureDatabaseOnly : 22|1@1+ (1,0) [0|0] "" DAS + SG_ UI_lssElkEnabled : 23|1@1+ (1,0) [0|0] "" DAS + SG_ UI_summonExitType : 24|2@1+ (1,0) [0|3] "" DAS + SG_ UI_summonEntryType : 26|2@1+ (1,0) [0|3] "" DAS + SG_ UI_selfParkRequest : 28|4@1+ (1,0) [0|15] "" DAS,PARK + SG_ UI_summonReverseDist : 32|6@1+ (1,0) [0|63] "" DAS + SG_ UI_undertakeAssistEnable : 38|1@1+ (1,0) [0|0] "" DAS + SG_ UI_adaptiveSetSpeedEnable : 39|1@1+ (1,0) [0|0] "" DAS + SG_ UI_drivingSide : 40|2@1+ (1,0) [0|3] "" DAS + SG_ UI_enableClipTelemetry : 42|1@1+ (1,0) [0|0] "" APP + SG_ UI_enableTripTelemetry : 43|1@1+ (1,0) [0|0] "" APP + SG_ UI_enableRoadSegmentTelemetry : 44|1@1+ (1,0) [0|0] "" APP + SG_ UI_followNavRouteEnable : 46|1@1+ (1,0) [0|0] "" APP + SG_ UI_ulcSpeedConfig : 48|2@1+ (1,0) [0|3] "" APP + SG_ UI_ulcBlindSpotConfig : 50|2@1+ (1,0) [0|3] "" APP + SG_ UI_autopilotAlwaysOn : 52|1@1+ (1,0) [0|1] "" APP + SG_ UI_accFromZero : 53|1@1+ (1,0) [0|1] "" APP + SG_ UI_alcOffHighwayEnable : 54|1@1+ (1,0) [0|1] "" APP + SG_ UI_validationLoop : 55|1@1+ (1,0) [0|1] "" APP + SG_ UI_ulcOffHighway : 56|1@1+ (1,0) [0|1] "" APP + SG_ UI_enableNavRouteCSA : 57|1@1+ (1,0) [0|1] "" APP + SG_ UI_enableCutinExperiments : 58|1@1+ (1,0) [0|1] "" APP + SG_ UI_source3D : 60|3@1+ (1,0) [0|7] "" APP + SG_ UI_enableVisionOnlyStops : 63|1@1+ (1,0) [0|1] "" APP + +BO_ 968 UI_driverAssistMapData: 8 GTW + SG_ UI_mapSpeedLimitDependency : 0|3@1+ (1,0) [0|0] "" DAS + SG_ UI_roadClass : 3|3@1+ (1,0) [0|0] "" DAS + SG_ UI_inSuperchargerGeofence : 6|1@1+ (1,0) [0|0] "" DAS + SG_ UI_mapSpeedUnits : 7|1@1+ (1,0) [0|0] "" DAS + SG_ UI_mapSpeedLimit : 8|5@1+ (1,0) [0|0] "" DAS + SG_ UI_mapSpeedLimitType : 13|3@1+ (1,0) [0|0] "" DAS + SG_ UI_countryCode : 16|10@1+ (1,0) [0|0] "" DAS + SG_ UI_streetCount : 26|2@1+ (1,0) [0|0] "" DAS + SG_ UI_gpsRoadMatch : 28|1@1+ (1,0) [0|0] "" DAS + SG_ UI_navRouteActive : 29|1@1+ (1,0) [0|0] "" DAS + SG_ UI_parallelAutoparkEnabled : 30|1@1+ (1,0) [0|1] "" DAS + SG_ UI_perpendicularAutoparkEnabled : 31|1@1+ (1,0) [0|1] "" DAS + SG_ UI_nextBranchDist : 32|5@1+ (10,0) [0|300] "m" DAS + SG_ UI_controlledAccess : 37|1@1+ (1,0) [0|0] "" DAS + SG_ UI_nextBranchLeftOffRamp : 38|1@1+ (1,0) [0|0] "" DAS + SG_ UI_nextBranchRightOffRamp : 39|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectLeftLane : 40|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectRightLane : 41|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectHPP : 42|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectNav : 43|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectLeftFreeSpace : 44|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectRightFreeSpace : 45|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectAutosteer : 46|1@1+ (1,0) [0|0] "" DAS + SG_ UI_rejectHandsOn : 47|1@1+ (1,0) [0|0] "" DAS + SG_ UI_acceptBottsDots : 48|1@1+ (1,0) [0|0] "" DAS + SG_ UI_autosteerRestricted : 49|1@1+ (1,0) [0|0] "" DAS + SG_ UI_pmmEnabled : 50|1@1+ (1,0) [0|0] "" DAS + SG_ UI_scaEnabled : 51|1@1+ (1,0) [0|0] "" DAS + SG_ UI_mapDataCounter : 52|4@1+ (1,0) [0|0] "" DAS + SG_ UI_mapDataChecksum : 56|8@1+ (1,0) [0|0] "" DAS + +BO_ 568 UI_driverAssistRoadSign: 8 GTW + SG_ UI_roadSign M : 0|8@1+ (1,0) [0|0] "" DAS + SG_ UI_splineLocConfidence : 40|7@1+ (1,0) [0|100] "" DAS + SG_ UI_splineID : 48|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ UI_roadSignCounter : 52|4@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_roadSignChecksum : 56|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_dummyData m0 : 8|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_stopSignStopLineDist m1 : 8|10@1+ (0.25,-8) [-8|247.5] "m" Vector__XXX + SG_ UI_stopSignStopLineConf m1 : 18|7@1+ (1,0) [0|100] "" Vector__XXX + SG_ UI_trafficLightStopLineDist m2 : 8|10@1+ (0.25,-8) [-8|247.5] "m" Vector__XXX + SG_ UI_trafficLightStopLineConf m2 : 18|7@1+ (1,0) [0|100] "" Vector__XXX + SG_ UI_baseMapSpeedLimitMPS m3 : 8|8@1+ (0.25,0) [0|63.75] "m/s" DAS + SG_ UI_bottomQrtlFleetSpeedMPS m3 : 16|8@1+ (0.25,0) [0|63.75] "m/s" DAS + SG_ UI_topQrtlFleetSpeedMPS m3 : 24|8@1+ (0.25,0) [0|63.75] "m/s" DAS + SG_ UI_meanFleetSplineSpeedMPS m4 : 8|8@1+ (0.25,0) [0|63.75] "m/s" DAS + SG_ UI_medianFleetSpeedMPS m4 : 16|8@1+ (0.25,0) [0|63.75] "m/s" DAS + SG_ UI_meanFleetSplineAccelMPS2 m4 : 24|8@1+ (0.05,-6.35) [-6.35|6.4] "m/s^2" DAS + SG_ UI_rampType m4 : 32|3@1+ (1,0) [0|7] "" DAS + SG_ UI_currSplineIdFull m5 : 8|32@1+ (1,0) [0|1] "" APP + + +BO_ 696 UI_radarMapData: 8 GTW + SG_ UI_radarTargetDx : 0|8@1+ (1,-95) [-95|160] "m" DAS + SG_ UI_radarTargetDxEnd : 8|8@1+ (1,0) [0|255] "m" DAS + SG_ UI_radarTargetTrustMap : 16|1@1+ (1,0) [0|1] "" DAS + SG_ UI_radarEnableBraking : 17|1@1+ (1,0) [0|1] "" DAS + SG_ UI_radarMapDataCounter : 52|4@1+ (1,0) [0|0] "" DAS + SG_ UI_radarMapDataChecksum : 56|8@1+ (1,0) [0|0] "" DAS + +BO_ 712 UI_roadCurvature: 8 GTW + SG_ UI_roadCurvC0 : 0|11@1- (0.02,0) [-20.48|20.46] "m" DAS + SG_ UI_roadCurvC1 : 11|10@1- (0.00075,0) [-0.384|0.38325] "1" DAS + SG_ UI_roadCurvC2 : 21|14@1- (7.5E-06,0) [-0.03072|0.03071625] "1/m" DAS + SG_ UI_roadCurvC3 : 35|13@1- (3E-08,0) [-0.00012288|0.00012285] "1/m2" DAS + SG_ UI_roadCurvRange : 48|6@1+ (4,0) [0|252] "m" DAS + SG_ UI_roadCurvHealth : 54|2@1+ (1,0) [0|0] "" DAS + SG_ UI_roadCurvChecksum : 56|8@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 582 UI_solarData: 5 GTW + SG_ UI_solarAzimuthAngle : 0|16@1- (1,0) [0|360] "deg" APP + SG_ UI_solarAzimuthAngleCarRef : 16|9@1- (1,0) [-180|180] "deg" APP + SG_ UI_isSunUp : 25|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_solarElevationAngle : 32|8@1- (1,0) [-90|90] "deg" APP + +BO_ 824 UI_status: 8 GTW + SG_ UI_touchActive : 0|1@1+ (1,0) [0|0] "" IC + SG_ UI_audioActive : 1|1@1+ (1,0) [0|0] "" IC + SG_ UI_bluetoothActive : 2|1@1+ (1,0) [0|0] "" IC + SG_ UI_cellActive : 3|1@1+ (1,0) [0|0] "" IC + SG_ UI_displayReady : 4|1@1+ (1,0) [0|0] "" IC + SG_ UI_gpsActive : 5|1@1+ (1,0) [0|0] "" IC + SG_ UI_wifiConnected : 6|1@1+ (1,0) [0|0] "" IC,APP + SG_ UI_systemActive : 7|1@1+ (1,0) [0|0] "" IC + SG_ UI_xmActive : 8|1@1+ (1,0) [0|0] "" IC + SG_ UI_displayOn : 9|1@1+ (1,0) [0|0] "" IC,APP + SG_ UI_readyForDrive : 10|1@1+ (1,0) [0|0] "" IC + SG_ UI_cellConnected : 11|1@1+ (1,0) [0|0] "" IC,APP + SG_ UI_vpnActive : 12|1@1+ (1,0) [0|0] "" IC,APP + SG_ UI_wifiActive : 13|1@1+ (1,0) [0|0] "" IC + SG_ UI_cameraActive : 14|1@1+ (1,0) [0|0] "" IC,APP + SG_ UI_usbActive : 15|1@1+ (1,0) [0|0] "" IC + SG_ UI_screenshotActive : 16|1@1+ (1,0) [0|0] "" IC,APP + SG_ UI_monitorModemPower : 17|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_factoryReset : 18|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ UI_cellNetworkTechnology : 20|4@1+ (1,0) [0|15] "" APP + SG_ UI_tegraCoreTemperature : 24|8@1+ (1,-64) [0|0] "deg C" IC + SG_ UI_tegraAmbientTemperature : 32|8@1+ (1,-64) [0|0] "deg C" IC + SG_ UI_googleWifiUsages : 40|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_autopilotTrial : 48|2@1+ (1,0) [0|0] "" APP + SG_ UI_cellSignalBars : 50|3@1+ (1,0) [0|7] "" APP + SG_ UI_hardwareType : 53|2@1+ (1,0) [0|3] "" APP + SG_ UI_developmentCar : 55|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_cellReceiverPower : 56|8@1+ (1,-128) [-128|127] "dB" APP + +BO_ 1064 UI_telemetryControl: 8 GTW + SG_ UI_TCR_enable : 0|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_moveStateStanding : 1|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_moveStateStopped : 2|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_moveStateMoving : 3|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_moveStateIndeterm : 4|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_classConstElem : 5|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_classMovingPed : 6|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_classMovingTwoWheel : 7|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_classMovingFourWheel : 8|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_classUnknown : 9|1@1+ (1,0) [0|0] "" DAS + SG_ UI_TCR_downSampleFactor : 16|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ UI_TCR_wExist : 24|5@1+ (1,0) [0|31] "" Vector__XXX + SG_ UI_TCR_vehSpeed : 32|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ UI_TCR_minRCS : 40|8@1+ (0.25,-14) [-14|49.75] "dB" Vector__XXX + SG_ UI_TCR_maxDy : 48|5@1+ (0.5,0) [0|15.5] "m" Vector__XXX + SG_ UI_TCR_maxObjects : 56|5@1+ (1,0) [0|31] "" Vector__XXX + SG_ UI_TCR_maxRoadClass : 61|3@1+ (1,0) [0|7] "" Vector__XXX + +BO_ 522 BrakeMessage: 8 XXX + SG_ driverBrakeStatus : 2|2@1+ (1,0) [0|3] "" XXX + +BO_ 921 AutopilotStatus: 8 XXX + SG_ autopilotStatus : 0|4@1+ (1,0) [0|0] "" XXX + +VAL_ 3 StW_Angl 16383 "SNA" ; +VAL_ 3 StW_AnglSens_Id 2 "MUST" 0 "PSBL" 1 "SELF" ; +VAL_ 3 StW_AnglSens_Stat 2 "ERR" 3 "ERR_INI" 1 "INI" 0 "OK" ; +VAL_ 3 StW_AnglSpd 16383 "SNA" ; +VAL_ 14 StW_AnglHP 16383 "SNA" ; +VAL_ 14 StW_AnglHP_Spd 16383 "SNA" ; +VAL_ 14 StW_AnglHP_Sens_Stat 3 "SNA" 2 "ERR" 1 "INI" 0 "OK" ; +VAL_ 14 StW_AnglHP_Sens_Id 3 "SNA" 2 "KOSTAL" 1 "DELPHI" 0 "TEST" ; +VAL_ 69 SpdCtrlLvr_Stat 32 "DN_1ST" 16 "UP_1ST" 8 "DN_2ND" 4 "UP_2ND" 2 "RWD" 1 "FWD" 0 "IDLE" ; +VAL_ 69 DTR_Dist_Rq 255 "SNA" 200 "ACC_DIST_7" 166 "ACC_DIST_6" 133 "ACC_DIST_5" 100 "ACC_DIST_4" 66 "ACC_DIST_3" 33 "ACC_DIST_2" 0 "ACC_DIST_1" ; +VAL_ 69 TurnIndLvr_Stat 3 "SNA" 2 "RIGHT" 1 "LEFT" 0 "IDLE" ; +VAL_ 69 HiBmLvr_Stat 3 "SNA" 2 "HIBM_FLSH_ON_PSD" 1 "HIBM_ON_PSD" 0 "IDLE" ; +VAL_ 69 WprWashSw_Psd 3 "SNA" 2 "WASH" 1 "TIPWIPE" 0 "NPSD" ; +VAL_ 69 WprWash_R_Sw_Posn_V2 3 "SNA" 2 "WASH" 1 "INTERVAL" 0 "OFF" ; +VAL_ 69 StW_Lvr_Stat 4 "STW_BACK" 3 "STW_FWD" 2 "STW_DOWN" 1 "STW_UP" 0 "NPSD" ; +VAL_ 69 StW_Cond_Psd 3 "SNA" 2 "DOWN" 1 "UP" 0 "NPSD" ; +VAL_ 69 HrnSw_Psd 3 "SNA" 2 "NDEF2" 1 "PSD" 0 "NPSD" ; +VAL_ 69 StW_Sw00_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 StW_Sw01_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 StW_Sw03_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 StW_Sw04_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 69 WprSw6Posn 7 "SNA" 6 "STAGE2" 5 "STAGE1" 4 "INTERVAL4" 3 "INTERVAL3" 2 "INTERVAL2" 1 "INTERVAL1" 0 "OFF" ; +VAL_ 257 GTW_epasControlType 0 "WITHOUT" 1 "WITH_ANGLE" 3 "WITH_BOTH" 2 "WITH_TORQUE" ; +VAL_ 109 StW_Sw_Stat3 7 "SNA" 6 "NDEF6" 5 "NDEF5" 4 "NDEF4" 3 "PLUS_MINUS" 2 "MINUS" 1 "PLUS" 0 "NPSD" ; +VAL_ 109 MsgTxmtId 3 "NDEF3" 2 "NDEF2" 1 "SCCM" 0 "EWM" ; +VAL_ 109 TSL_RND_Posn_StW 15 "SNA" 8 "D" 6 "INI" 4 "N_DOWN" 2 "N_UP" 1 "R" 0 "IDLE" ; +VAL_ 109 TSL_P_Psd_StW 3 "SNA" 2 "INI" 1 "PSD" 0 "IDLE" ; +VAL_ 257 GTW_epasEmergencyOn 1 "EMERGENCY_POWER" 0 "NONE" ; +VAL_ 257 GTW_epasLDWEnabled 1 "ALLOWED" 0 "INHIBITED" ; +VAL_ 257 GTW_epasPowerMode 0 "DRIVE_OFF" 1 "DRIVE_ON" 3 "LOAD_SHED" 2 "SHUTTING_DOWN" 15 "SNA" ; +VAL_ 257 GTW_epasTuneRequest 1 "DM_COMFORT" 3 "DM_SPORT" 2 "DM_STANDARD" 0 "FAIL_SAFE_DEFAULT" 4 "RWD_COMFORT" 6 "RWD_SPORT" 5 "RWD_STANDARD" 7 "SNA" ; +VAL_ 264 DI_torqueDriver -4096 "SNA" ; +VAL_ 264 DI_torqueMotor -4096 "SNA" ; +VAL_ 264 DI_soptState 7 "SOPT_TEST_SNA" 4 "SOPT_TEST_NOT_RUN" 3 "SOPT_TEST_PASSED" 2 "SOPT_TEST_FAILED" 1 "SOPT_TEST_IN_PROGRESS" 0 "SOPT_PRE_TEST" ; +VAL_ 264 DI_motorRPM -32768 "SNA" ; +VAL_ 264 DI_pedalPos 255 "SNA" ; +VAL_ 280 DI_torqueEstimate -2048 "SNA" ; +VAL_ 280 DI_gear 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ; +VAL_ 280 DI_brakePedal 1 "Applied" 0 "Not_applied" ; +VAL_ 280 DI_vehicleSpeed 4095 "SNA" ; +VAL_ 280 DI_gearRequest 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ; +VAL_ 280 DI_torqueInterfaceFailure 1 "TORQUE_INTERFACE_FAILED" 0 "TORQUE_INTERFACE_NORMAL" ; +VAL_ 280 DI_brakePedalState 3 "SNA" 2 "INVALID" 1 "ON" 0 "OFF" ; +VAL_ 280 DI_epbParkRequest 1 "Park_requested" 0 "No_request" ; +VAL_ 280 DI_epbInterfaceReady 1 "EPB_INTERFACE_READY" 0 "EPB_INTERFACE_NOT_READY" ; +VAL_ 309 ESP_absBrakeEvent 1 "ACTIVE" 0 "NOT_ACTIVE" ; +VAL_ 309 ESP_brakeDiscWipingActive 1 "ACTIVE" 0 "INACTIVE" ; +VAL_ 309 ESP_brakeLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_espFaultLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_espLampFlash 1 "FLASH" 0 "OFF" ; +VAL_ 309 ESP_hillStartAssistActive 1 "ACTIVE" 0 "INACTIVE" 2 "NOT_AVAILABLE" 3 "SNA" ; +VAL_ 309 ESP_absFaultLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_espOffLamp 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_stabilityControlSts 2 "ENGAGED" 3 "FAULTED" 5 "INIT" 4 "NOT_CONFIGURED" 0 "OFF" 1 "ON" ; +VAL_ 309 ESP_tcLampFlash 1 "FLASH" 0 "OFF" ; +VAL_ 568 UI_mapSpeedLimit 31 "SNA" 30 "UNLIMITED" 29 "LESS_OR_EQ_160" 28 "LESS_OR_EQ_150" 27 "LESS_OR_EQ_140" 26 "LESS_OR_EQ_130" 25 "LESS_OR_EQ_120" 24 "LESS_OR_EQ_115" 23 "LESS_OR_EQ_110" 22 "LESS_OR_EQ_105" 21 "LESS_OR_EQ_100" 20 "LESS_OR_EQ_95" 19 "LESS_OR_EQ_90" 18 "LESS_OR_EQ_85" 17 "LESS_OR_EQ_80" 16 "LESS_OR_EQ_75" 15 "LESS_OR_EQ_70" 14 "LESS_OR_EQ_65" 13 "LESS_OR_EQ_60" 12 "LESS_OR_EQ_55" 11 "LESS_OR_EQ_50" 10 "LESS_OR_EQ_45" 9 "LESS_OR_EQ_40" 8 "LESS_OR_EQ_35" 7 "LESS_OR_EQ_30" 6 "LESS_OR_EQ_25" 5 "LESS_OR_EQ_20" 4 "LESS_OR_EQ_15" 3 "LESS_OR_EQ_10" 2 "LESS_OR_EQ_7" 1 "LESS_OR_EQ_5" 0 "UNKNOWN" ; +VAL_ 522 driverBrakeStatus 2 "APPLIED" 1 "NOT_APPLIED" ; +VAL_ 760 UI_mapSpeedLimitUnits 1 "KPH" 0 "MPH" ; +VAL_ 760 UI_userSpeedOffsetUnits 1 "KPH" 0 "MPH" ; +VAL_ 643 AirTemp_Insd 255 "SNA" ; +VAL_ 643 AirTemp_Outsd 254 "INIT" 255 "SNA" ; +VAL_ 643 Bckl_Sw_RL_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ; +VAL_ 643 Bckl_Sw_RM_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ; +VAL_ 643 Bckl_Sw_RR_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ; +VAL_ 643 DL_RLtch_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_FL_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_FR_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_RL_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 DrRLtch_RR_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 EngHd_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ; +VAL_ 643 LgtSens_Night 0 "DAY" 1 "NIGHT" ; +VAL_ 643 MPkBrk_Stat 1 "ENGG" 0 "RELS" ; +VAL_ 643 RevGr_Engg 0 "DISENGG" 1 "ENGG" 2 "NDEF2" 3 "SNA" ; +VAL_ 643 StW_Cond_Stat 3 "BLINK" 1 "NDEF1" 0 "OFF" 2 "ON" ; +VAL_ 643 Trlr_Stat 2 "NDEF2" 0 "NONE" 1 "OK" 3 "SNA" ; +VAL_ 792 BOOT_STATE 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 CERRD 1 "CAN error detect" 0 "no Can error detected" ; +VAL_ 792 DAY 1 "Init" 0 "SNA" ; +VAL_ 792 DOOR_STATE_FL 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_FR 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_FrontTrunk 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_RL 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 DOOR_STATE_RR 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; +VAL_ 792 GTW_updateInProgress 1 "IN_PROGRESS" 2 "IN_PROGRESS_NOT_USED" 3 "IN_PROGRESS_SNA" 0 "NOT_IN_PROGRESS" ; +VAL_ 792 Hour 30 "Init" 31 "SNA" ; +VAL_ 792 MCU_factoryMode 1 "FACTORY_MODE" 0 "NORMAL_MODE" ; +VAL_ 792 MCU_transportModeOn 0 "NORMAL_MODE" ; +VAL_ 792 MINUTE 62 "Init" 63 "SNA" ; +VAL_ 792 MONTH 1 "Init" 15 "SNA" ; +VAL_ 792 SECOND 62 "Init" 63 "SNA" ; +VAL_ 792 YEAR 126 "Init" 127 "SNA" ; +VAL_ 872 DI_aebState 2 "ENABLED" 4 "FAULT" 7 "SNA" 1 "STANDBY" 3 "STANDSTILL" 0 "UNAVAILABLE" ; +VAL_ 872 DI_analogSpeed 4095 "SNA" ; +VAL_ 872 DI_cruiseState 2 "ENABLED" 5 "FAULT" 0 "OFF" 4 "OVERRIDE" 7 "PRE_CANCEL" 6 "PRE_FAULT" 1 "STANDBY" 3 "STANDSTILL" ; +VAL_ 872 DI_digitalSpeed 255 "SNA" ; +VAL_ 872 DI_immobilizerState 2 "AUTHENTICATING" 3 "DISARMED" 6 "FAULT" 4 "IDLE" 0 "INIT_SNA" 1 "REQUEST" 5 "RESET" ; +VAL_ 872 DI_speedUnits 1 "KPH" 0 "MPH" ; +VAL_ 872 DI_state 3 "ABORT" 4 "ENABLE" 2 "FAULT" 1 "STANDBY" 0 "UNAVAILABLE" ; +VAL_ 872 DI_systemState 3 "ABORT" 4 "ENABLE" 2 "FAULT" 1 "STANDBY" 0 "UNAVAILABLE" ; +VAL_ 872 DI_vehicleHoldState 2 "BLEND_IN" 4 "BLEND_OUT" 6 "FAULT" 7 "INIT" 5 "PARK" 1 "STANDBY" 3 "STANDSTILL" 0 "UNAVAILABLE" ; +VAL_ 880 EPAS_currentTuneMode 1 "DM_COMFORT" 3 "DM_SPORT" 2 "DM_STANDARD" 0 "FAIL_SAFE_DEFAULT" 4 "RWD_COMFORT" 6 "RWD_SPORT" 5 "RWD_STANDARD" 7 "UNAVAILABLE" ; +VAL_ 880 EPAS_eacErrorCode 14 "EAC_ERROR_EPB_INHIBIT" 3 "EAC_ERROR_HANDS_ON" 7 "EAC_ERROR_HIGH_ANGLE_RATE_REQ" 9 "EAC_ERROR_HIGH_ANGLE_RATE_SAFETY" 6 "EAC_ERROR_HIGH_ANGLE_REQ" 8 "EAC_ERROR_HIGH_ANGLE_SAFETY" 10 "EAC_ERROR_HIGH_MMOT_SAFETY" 11 "EAC_ERROR_HIGH_TORSION_SAFETY" 0 "EAC_ERROR_IDLE" 12 "EAC_ERROR_LOW_ASSIST" 2 "EAC_ERROR_MAX_SPEED" 1 "EAC_ERROR_MIN_SPEED" 13 "EAC_ERROR_PINION_VEL_DIFF" 4 "EAC_ERROR_TMP_FAULT" 5 "EAR_ERROR_MAX_STEER_DELTA" 15 "SNA" ; +VAL_ 880 EPAS_eacStatus 2 "EAC_ACTIVE" 1 "EAC_AVAILABLE" 3 "EAC_FAULT" 0 "EAC_INHIBITED" 4 "SNA" ; +VAL_ 880 EPAS_handsOnLevel 0 "0" 1 "1" 2 "2" 3 "3" ; +VAL_ 880 EPAS_steeringFault 1 "FAULT" 0 "NO_FAULT" ; +VAL_ 880 EPAS_steeringRackForce 1022 "NOT_IN_SPEC" 1023 "SNA" ; +VAL_ 880 EPAS_steeringReduced 0 "NORMAL_ASSIST" 1 "REDUCED_ASSIST" ; +VAL_ 880 EPAS_torsionBarTorque 0 "SEE_SPECIFICATION" 4095 "SNA" 4094 "UNDEFINABLE_DATA" ; +VAL_ 904 MCU_clusterReadyForDrive 0 "NO_SNA" 1 "YES" ; +VAL_ 921 autopilotStatus 5 "ACTIVE_NAVIGATE_ON_AUTOPILOT" 4 "ACTIVE_2" 3 "ACTIVE_1" 2 "AVAILABLE" 1 "UNAVAILABLE" 0 "DISABLED" ; +VAL_ 1160 DAS_steeringAngleRequest 16384 "ZERO_ANGLE" ; +VAL_ 1160 DAS_steeringControlType 1 "ANGLE_CONTROL" 3 "DISABLED" 0 "NONE" 2 "RESERVED" ; +VAL_ 1160 DAS_steeringHapticRequest 1 "ACTIVE" 0 "IDLE" ; + + +CM_ "CHFFR_METRIC 1160 DAS_steeringAngleRequest STEER_ANGLE 0.1098666 180; CHFFR_METRIC 264 DI_motorRPM ENGINE_RPM 1 0"; diff --git a/opendbc/toyota_avalon_2017_pt_generated.dbc b/opendbc/toyota_avalon_2017_pt_generated.dbc index 369c0e84c..505322e2e 100644 --- a/opendbc/toyota_avalon_2017_pt_generated.dbc +++ b/opendbc/toyota_avalon_2017_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc index 35a165a17..daf2baeee 100644 --- a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc +++ b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc index aec13d864..1e59b4c77 100644 --- a/opendbc/toyota_corolla_2017_pt_generated.dbc +++ b/opendbc/toyota_corolla_2017_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_highlander_2017_pt_generated.dbc b/opendbc/toyota_highlander_2017_pt_generated.dbc index b96c4b28d..f4ac25165 100644 --- a/opendbc/toyota_highlander_2017_pt_generated.dbc +++ b/opendbc/toyota_highlander_2017_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc index 1e4964a91..25697c7ab 100644 --- a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc +++ b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc b/opendbc/toyota_nodsu_hybrid_pt_generated.dbc index aac755dbd..687f5dbe2 100644 --- a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc +++ b/opendbc/toyota_nodsu_hybrid_pt_generated.dbc @@ -193,7 +193,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -226,6 +226,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -363,6 +366,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -390,6 +394,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_nodsu_pt_generated.dbc b/opendbc/toyota_nodsu_pt_generated.dbc index 810c323a3..59eb8abf6 100644 --- a/opendbc/toyota_nodsu_pt_generated.dbc +++ b/opendbc/toyota_nodsu_pt_generated.dbc @@ -193,7 +193,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -226,6 +226,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -363,6 +366,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -390,6 +394,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc index 502ef852f..ca62cf1d0 100644 --- a/opendbc/toyota_prius_2017_pt_generated.dbc +++ b/opendbc/toyota_prius_2017_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc index 4be2a2ed2..a9bb57e0f 100644 --- a/opendbc/toyota_rav4_2017_pt_generated.dbc +++ b/opendbc/toyota_rav4_2017_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc index b64182e0f..d7b55944f 100644 --- a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc +++ b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc index 12c2afe45..34fdfc7ee 100644 --- a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc +++ b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc @@ -163,7 +163,7 @@ BO_ 742 LEAD_INFO: 8 DSU BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX @@ -196,6 +196,9 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX @@ -333,6 +336,7 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; @@ -360,6 +364,7 @@ VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; diff --git a/opendbc/vw_mqb_2010.dbc b/opendbc/vw_mqb_2010.dbc index 49f2541e6..63477a1cb 100644 --- a/opendbc/vw_mqb_2010.dbc +++ b/opendbc/vw_mqb_2010.dbc @@ -1334,6 +1334,14 @@ BO_ 981 Licht_Anf_01: 8 XXX BO_ 1440 RLS_01: 8 XXX BO_ 870 Blinkmodi_02: 8 XXX + SG_ Hazard_Switch : 20|1@1+ (1,0) [0|1] "" XXX + SG_ Comfort_Signal_Left : 23|1@1+ (1,0) [0|1] "" XXX + SG_ Comfort_Signal_Right : 24|1@1+ (1,0) [0|1] "" XXX + SG_ Left_Turn_Exterior_Bulb_1 : 25|1@1+ (1,0) [0|1] "" XXX + SG_ Right_Turn_Exterior_Bulb_1 : 26|1@1+ (1,0) [0|1] "" XXX + SG_ Left_Turn_Exterior_Bulb_2 : 27|1@1+ (1,0) [0|1] "" XXX + SG_ Right_Turn_Exterior_Bulb_2 : 28|1@1+ (1,0) [0|1] "" XXX + SG_ Fast_Send_Rate_Active : 37|1@1+ (1,0) [0|1] "" XXX BO_ 1385 HVEM_04: 8 XXX @@ -1364,6 +1372,14 @@ CM_ SG_ 294 254 "May be zero when sent by older cameras"; CM_ SG_ 294 Assist_Torque "Heading control input, torque"; CM_ SG_ 294 Assist_VZ "Heading control input, direction (sign)"; CM_ SG_ 294 HCA_Available "Must be 1 for steering rack to accept HCA commands"; +CM_ SG_ 870 Hazard_Switch "Four-way flashers active"; +CM_ SG_ 870 Comfort_Signal_Left "Comfort turn signal active, left"; +CM_ SG_ 870 Comfort_Signal_Right "Comfort turn signal active, right"; +CM_ SG_ 870 Left_Turn_Exterior_Bulb_1 "Probably front"; +CM_ SG_ 870 Right_Turn_Exterior_Bulb_1 "Probably front"; +CM_ SG_ 870 Left_Turn_Exterior_Bulb_2 "Probably rear"; +CM_ SG_ 870 Right_Turn_Exterior_Bulb_2 "Probably rear"; +CM_ SG_ 870 Fast_Send_Rate_Active "CAN message send rate"; CM_ SG_ 919 LDW_DLC "Probable DLC (distance to line crossing)"; CM_ SG_ 919 LDW_TLC "Probable TLC (time to line crossing)"; CM_ SG_ 919 LDW_Unknown "Might be a steering pressed / driver active flag"; @@ -1383,3 +1399,4 @@ VAL_ 159 EPS_HCA_Status 0 "disabled" 1 "initializing" 2 "fault" 3 "ready" 4 "rej VAL_ 173 GE_Fahrstufe 5 "P" 6 "R" 7 "N" 8 "D" 9 "S" 10 "E" 14 "T"; VAL_ 391 GearPosition 2 "P" 3 "R" 4 "N" 5 "D" 6 "D"; VAL_ 391 RegenBrakingMode 0 "default" 1 "B1" 2 "B2" 3 "B3"; +VAL_ 870 Fast_Send_Rate_Active 0 "1 Hz" 1 "50 Hz"; diff --git a/panda/board/SConscript b/panda/board/SConscript index 167da9e24..02e582463 100644 --- a/panda/board/SConscript +++ b/panda/board/SConscript @@ -1,16 +1,13 @@ import os import subprocess -EON = os.path.isfile('/EON') -TICI = os.path.isfile('/TICI') -PC = not (EON or TICI) - PREFIX = "arm-none-eabi-" BUILDER = "DEV" if os.getenv("PEDAL"): PROJECT = "pedal" - STARTUP_FILE = "startup_stm32f205xx.s" + STARTUP_FILE = "stm32fx/startup_stm32f205xx.s" + LINKER_SCRIPT = "stm32fx/stm32fx_flash.ld" MAIN = "pedal/main.c" PROJECT_FLAGS = [ "-mcpu=cortex-m3", @@ -20,10 +17,13 @@ if os.getenv("PEDAL"): "-O2", "-DPEDAL", ] + if os.getenv("PEDAL_USB"): + PROJECT_FLAGS.append("-DPEDAL_USB") else: PROJECT = "panda" - STARTUP_FILE = "startup_stm32f413xx.s" + STARTUP_FILE = "stm32fx/startup_stm32f413xx.s" + LINKER_SCRIPT = "stm32fx/stm32fx_flash.ld" MAIN = "main.c" PROJECT_FLAGS = [ "-mcpu=cortex-m4", @@ -34,12 +34,9 @@ else: "-fsingle-precision-constant", "-Os", "-g", + "-DPANDA", ] - if not PC: - PROJECT_FLAGS += ["-DEON"] - BUILDER = "EON" - def get_version(builder, build_type): version_file = File('../VERSION').srcnode().abspath @@ -85,7 +82,7 @@ def objcopy(source, target, env, for_signature): return '$OBJCOPY -O binary %s %s' % (source[0], target[0]) -linkerscript_fn = File("stm32_flash.ld").srcnode().abspath +linkerscript_fn = File(LINKER_SCRIPT).srcnode().abspath flags = [ "-Wall", @@ -112,7 +109,7 @@ else: flags += ["-DALLOW_DEBUG"] includes = [ - "inc", + "stm32fx/inc", "..", ".", ] diff --git a/panda/board/boards/black.h b/panda/board/boards/black.h index fa5a542d0..9333402fa 100644 --- a/panda/board/boards/black.h +++ b/panda/board/boards/black.h @@ -213,9 +213,6 @@ void black_init(void) { if (car_harness_status == HARNESS_STATUS_FLIPPED) { can_flip_buses(0, 2); } - - // init multiplexer - can_set_obd(car_harness_status, false); } const harness_configuration black_harness_config = { @@ -235,6 +232,11 @@ const harness_configuration black_harness_config = { const board board_black = { .board_type = "Black", .harness_config = &black_harness_config, + .has_gps = true, + .has_hw_gmlan = false, + .has_obd = true, + .has_lin = false, + .has_rtc = false, .init = black_init, .enable_can_transceiver = black_enable_can_transceiver, .enable_can_transceivers = black_enable_can_transceivers, diff --git a/panda/board/board_declarations.h b/panda/board/boards/board_declarations.h similarity index 91% rename from panda/board/board_declarations.h rename to panda/board/boards/board_declarations.h index 963539e00..57957f760 100644 --- a/panda/board/board_declarations.h +++ b/panda/board/boards/board_declarations.h @@ -18,6 +18,11 @@ typedef void (*board_set_siren)(bool enabled); struct board { const char *board_type; const harness_configuration *harness_config; + const bool has_gps; + const bool has_hw_gmlan; + const bool has_obd; + const bool has_lin; + const bool has_rtc; board_init init; board_enable_can_transceiver enable_can_transceiver; board_enable_can_transceivers enable_can_transceivers; @@ -69,11 +74,3 @@ struct board { // ********************* Globals ********************** uint8_t usb_power_mode = USB_POWER_NONE; - -// ************ Board function prototypes ************* -bool board_has_gps(void); -bool board_has_gmlan(void); -bool board_has_obd(void); -bool board_has_lin(void); -bool board_has_rtc(void); -bool board_has_relay(void); diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h index 592155fb6..010aa1a4d 100644 --- a/panda/board/boards/dos.h +++ b/panda/board/boards/dos.h @@ -204,9 +204,6 @@ void dos_init(void) { can_flip_buses(0, 2); } - // init multiplexer - can_set_obd(car_harness_status, false); - // Init clock source as internal free running dos_set_clock_source_mode(CLOCK_SOURCE_MODE_FREE_RUNNING); } @@ -228,6 +225,11 @@ const harness_configuration dos_harness_config = { const board board_dos = { .board_type = "Dos", .harness_config = &dos_harness_config, + .has_gps = false, + .has_hw_gmlan = false, + .has_obd = true, + .has_lin = false, + .has_rtc = true, .init = dos_init, .enable_can_transceiver = dos_enable_can_transceiver, .enable_can_transceivers = dos_enable_can_transceivers, diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h index bd5b1559e..3a2f3b960 100644 --- a/panda/board/boards/grey.h +++ b/panda/board/boards/grey.h @@ -36,6 +36,11 @@ void grey_set_gps_mode(uint8_t mode) { const board board_grey = { .board_type = "Grey", .harness_config = &white_harness_config, + .has_gps = true, + .has_hw_gmlan = true, + .has_obd = false, + .has_lin = true, + .has_rtc = false, .init = grey_init, .enable_can_transceiver = white_enable_can_transceiver, .enable_can_transceivers = white_enable_can_transceivers, diff --git a/panda/board/boards/pedal.h b/panda/board/boards/pedal.h index 31abe9c5c..bb70923b4 100644 --- a/panda/board/boards/pedal.h +++ b/panda/board/boards/pedal.h @@ -109,6 +109,11 @@ const harness_configuration pedal_harness_config = { const board board_pedal = { .board_type = "Pedal", .harness_config = &pedal_harness_config, + .has_gps = false, + .has_hw_gmlan = false, + .has_obd = false, + .has_lin = false, + .has_rtc = false, .init = pedal_init, .enable_can_transceiver = pedal_enable_can_transceiver, .enable_can_transceivers = pedal_enable_can_transceivers, diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h index cc9c4c0dc..dc5fbd493 100644 --- a/panda/board/boards/uno.h +++ b/panda/board/boards/uno.h @@ -250,9 +250,6 @@ void uno_init(void) { can_flip_buses(0, 2); } - // init multiplexer - can_set_obd(car_harness_status, false); - // Switch to phone usb mode if harness connection is powered by less than 7V if(adc_get_voltage() < 7000U){ uno_set_usb_switch(true); @@ -281,6 +278,11 @@ const harness_configuration uno_harness_config = { const board board_uno = { .board_type = "Uno", .harness_config = &uno_harness_config, + .has_gps = true, + .has_hw_gmlan = false, + .has_obd = true, + .has_lin = false, + .has_rtc = true, .init = uno_init, .enable_can_transceiver = uno_enable_can_transceiver, .enable_can_transceivers = uno_enable_can_transceivers, diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h index 44d8f512b..14f026fa8 100644 --- a/panda/board/boards/white.h +++ b/panda/board/boards/white.h @@ -78,13 +78,6 @@ void white_set_gps_mode(uint8_t mode) { set_gpio_output(GPIOC, 14, 0); set_gpio_output(GPIOC, 5, 0); break; -#ifndef EON - case GPS_ENABLED: - // ESP ON - set_gpio_output(GPIOC, 14, 1); - set_gpio_output(GPIOC, 5, 1); - break; -#endif case GPS_BOOTMODE: set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 0); @@ -158,71 +151,8 @@ uint32_t white_read_current(void){ return adc_get(ADCCHAN_CURRENT); } -uint32_t marker = 0; void white_usb_power_mode_tick(uint32_t uptime){ - - // on EON or BOOTSTUB, no state machine -#if !defined(BOOTSTUB) && !defined(EON) - #define CURRENT_THRESHOLD 0xF00U - #define CLICKS 5U // 5 seconds to switch modes - - uint32_t current = white_read_current(); - - // ~0x9a = 500 ma - // puth(current); puts("\n"); - - switch (usb_power_mode) { - case USB_POWER_CLIENT: - if ((uptime - marker) >= CLICKS) { - if (!is_enumerated) { - puts("USBP: didn't enumerate, switching to CDP mode\n"); - // switch to CDP - white_set_usb_power_mode(USB_POWER_CDP); - marker = uptime; - } - } - // keep resetting the timer if it's enumerated - if (is_enumerated) { - marker = uptime; - } - break; - case USB_POWER_CDP: - // been CLICKS clicks since we switched to CDP - if ((uptime - marker) >= CLICKS) { - // measure current draw, if positive and no enumeration, switch to DCP - if (!is_enumerated && (current < CURRENT_THRESHOLD)) { - puts("USBP: no enumeration with current draw, switching to DCP mode\n"); - white_set_usb_power_mode(USB_POWER_DCP); - marker = uptime; - } - } - // keep resetting the timer if there's no current draw in CDP - if (current >= CURRENT_THRESHOLD) { - marker = uptime; - } - break; - case USB_POWER_DCP: - // been at least CLICKS clicks since we switched to DCP - if ((uptime - marker) >= CLICKS) { - // if no current draw, switch back to CDP - if (current >= CURRENT_THRESHOLD) { - puts("USBP: no current draw, switching back to CDP mode\n"); - white_set_usb_power_mode(USB_POWER_CDP); - marker = uptime; - } - } - // keep resetting the timer if there's current draw in DCP - if (current < CURRENT_THRESHOLD) { - marker = uptime; - } - break; - default: - puts("USB power mode invalid\n"); // set_usb_power_mode prevents assigning invalid values - break; - } -#else UNUSED(uptime); -#endif } void white_set_ir_power(uint8_t percentage){ @@ -313,7 +243,7 @@ void white_grey_common_init(void) { // Init usb power mode uint32_t voltage = adc_get_voltage(); // Init in CDP mode only if panda is powered by 12V. - // Otherwise a PC would not be able to flash a standalone panda with EON build + // Otherwise a PC would not be able to flash a standalone panda if (voltage > 8000U) { // 8V threshold white_set_usb_power_mode(USB_POWER_CDP); } else { @@ -335,6 +265,11 @@ const harness_configuration white_harness_config = { const board board_white = { .board_type = "White", .harness_config = &white_harness_config, + .has_gps = false, + .has_hw_gmlan = true, + .has_obd = false, + .has_lin = true, + .has_rtc = false, .init = white_init, .enable_can_transceiver = white_enable_can_transceiver, .enable_can_transceivers = white_enable_can_transceivers, diff --git a/panda/board/bootstub.c b/panda/board/bootstub.c index 1521b5324..1541a31d2 100644 --- a/panda/board/bootstub.c +++ b/panda/board/bootstub.c @@ -3,62 +3,24 @@ #define VERS_TAG 0x53524556 #define MIN_VERSION 2 -#include "config.h" -#include "obj/gitversion.h" - -#ifdef STM32F4 - #define PANDA - #include "stm32f4xx.h" - #include "stm32f4xx_hal_gpio_ex.h" -#else - #include "stm32f2xx.h" - #include "stm32f2xx_hal_gpio_ex.h" -#endif - -// ******************** Prototypes ******************** -void puts(const char *a){ UNUSED(a); } -void puth(unsigned int i){ UNUSED(i); } -void puth2(unsigned int i){ UNUSED(i); } -typedef struct board board; -typedef struct harness_configuration harness_configuration; -// No CAN support on bootloader -void can_flip_buses(uint8_t bus1, uint8_t bus2){UNUSED(bus1); UNUSED(bus2);} -void can_set_obd(int harness_orientation, bool obd){UNUSED(harness_orientation); UNUSED(obd);} - -// ********************* Globals ********************** -int hw_type = 0; -const board *current_board; - // ********************* Includes ********************* -#include "libc.h" -#include "provision.h" -#include "critical.h" -#include "faults.h" +#include "config.h" -#include "drivers/registers.h" -#include "drivers/interrupts.h" -#include "drivers/clock.h" -#include "drivers/llgpio.h" -#include "drivers/adc.h" #include "drivers/pwm.h" - -#include "board.h" - -#include "gpio.h" - -#include "drivers/spi.h" #include "drivers/usb.h" -//#include "drivers/uart.h" + +#include "early_init.h" +#include "provision.h" #include "crypto/rsa.h" #include "crypto/sha.h" #include "obj/cert.h" - +#include "obj/gitversion.h" #include "spi_flasher.h" void __initialize_hardware_early(void) { - early(); + early_initialization(); } void fail(void) { @@ -77,7 +39,7 @@ int main(void) { disable_interrupts(); clock_init(); - detect_configuration(); + detect_external_debug_serial(); detect_board_type(); if (enter_bootloader_mode == ENTER_SOFTLOADER_MAGIC) { @@ -121,4 +83,3 @@ good: ((void(*)(void)) _app_start[1])(); return 0; } - diff --git a/panda/board/bootstub_declarations.h b/panda/board/bootstub_declarations.h new file mode 100644 index 000000000..b247458f9 --- /dev/null +++ b/panda/board/bootstub_declarations.h @@ -0,0 +1,14 @@ +// ******************** Prototypes ******************** +void puts(const char *a){ UNUSED(a); } +void puth(uint8_t i){ UNUSED(i); } +void puth2(uint8_t i){ UNUSED(i); } +typedef struct board board; +typedef struct harness_configuration harness_configuration; +// No CAN support on bootloader +void can_flip_buses(uint8_t bus1, uint8_t bus2){UNUSED(bus1); UNUSED(bus2);} +void pwm_init(TIM_TypeDef *TIM, uint8_t channel); +void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage); + +// ********************* Globals ********************** +uint8_t hw_type = 0; +const board *current_board; diff --git a/panda/board/config.h b/panda/board/config.h index 335d2e1ec..d66c65c52 100644 --- a/panda/board/config.h +++ b/panda/board/config.h @@ -7,22 +7,14 @@ //#define DEBUG_SPI //#define DEBUG_FAULTS -#ifdef STM32F4 - #define PANDA - #include "stm32f4xx.h" -#else - #include "stm32f2xx.h" -#endif - #define USB_VID 0xbbaaU #ifdef BOOTSTUB -#define USB_PID 0xddeeU + #define USB_PID 0xddeeU #else -#define USB_PID 0xddccU + #define USB_PID 0xddccU #endif -#include #define NULL ((void*)0) #define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) @@ -42,8 +34,7 @@ #define MAX_RESP_LEN 0x40U -// Around (1Mbps / 8 bits/byte / 12 bytes per message) -#define CAN_INTERRUPT_RATE 12000U +#include +#include "stm32fx/stm32fx_config.h" #endif - diff --git a/panda/board/crc.h b/panda/board/crc.h index ab969e517..0d62dd316 100644 --- a/panda/board/crc.h +++ b/panda/board/crc.h @@ -1,6 +1,7 @@ uint8_t crc_checksum(uint8_t *dat, int len, const uint8_t poly) { - uint8_t crc = 0xFF; - int i, j; + uint8_t crc = 0xFFU; + int i; + int j; for (i = len - 1; i >= 0; i--) { crc ^= dat[i]; for (j = 0; j < 8; j++) { diff --git a/panda/board/drivers/can.h b/panda/board/drivers/can.h index 2ca7cbc71..6ec13362a 100644 --- a/panda/board/drivers/can.h +++ b/panda/board/drivers/can.h @@ -18,10 +18,13 @@ uint32_t can_rx_errs = 0; uint32_t can_send_errs = 0; uint32_t can_fwd_errs = 0; uint32_t gmlan_send_errs = 0; -extern int can_live, pending_can_live; + +extern int can_live; +extern int pending_can_live; // must reinit after changing these -extern int can_loopback, can_silent; +extern int can_loopback; +extern int can_silent; extern uint32_t can_speed[4]; void can_set_forwarding(int from, int to); @@ -42,19 +45,23 @@ uint32_t ignition_can_cnt = 0U; #define ALL_CAN_SILENT 0xFF #define ALL_CAN_LIVE 0 -int can_live = 0, pending_can_live = 0, can_loopback = 0, can_silent = ALL_CAN_SILENT; +int can_live = 0; +int pending_can_live = 0; +int can_loopback = 0; +int can_silent = ALL_CAN_SILENT; // ********************* instantiate queues ********************* - #define can_buffer(x, size) \ CAN_FIFOMailBox_TypeDef elems_##x[size]; \ - can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = size, .elems = (CAN_FIFOMailBox_TypeDef *)&elems_##x }; + can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = (size), .elems = (CAN_FIFOMailBox_TypeDef *)&(elems_##x) }; can_buffer(rx_q, 0x1000) can_buffer(tx1_q, 0x100) can_buffer(tx2_q, 0x100) can_buffer(tx3_q, 0x100) can_buffer(txgmlan_q, 0x100) +// FIXME: +// cppcheck-suppress misra-c2012-9.3 can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q}; // global CAN stats @@ -65,7 +72,6 @@ int can_err_cnt = 0; int can_overflow_cnt = 0; // ********************* interrupt safe queue ********************* - bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { bool ret = 0; @@ -181,7 +187,7 @@ void can_flip_buses(uint8_t bus1, uint8_t bus2){ // TODO: Cleanup with new abstraction void can_set_gmlan(uint8_t bus) { - if(board_has_gmlan()){ + if(current_board->has_hw_gmlan){ // first, disable GMLAN on prev bus uint8_t prev_bus = can_num_lookup[3]; if (bus != prev_bus) { @@ -229,34 +235,6 @@ void can_set_gmlan(uint8_t bus) { } } -// TODO: remove -void can_set_obd(uint8_t harness_orientation, bool obd){ - if(obd){ - puts("setting CAN2 to be OBD\n"); - } else { - puts("setting CAN2 to be normal\n"); - } - if(board_has_obd()){ - if(obd != (bool)(harness_orientation == HARNESS_STATUS_NORMAL)){ - // B5,B6: disable normal mode - set_gpio_mode(GPIOB, 5, MODE_INPUT); - set_gpio_mode(GPIOB, 6, MODE_INPUT); - // B12,B13: CAN2 mode - set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); - } else { - // B5,B6: CAN2 mode - set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - // B12,B13: disable normal mode - set_gpio_mode(GPIOB, 12, MODE_INPUT); - set_gpio_mode(GPIOB, 13, MODE_INPUT); - } - } else { - puts("OBD CAN not available on this board\n"); - } -} - // CAN error void can_sce(CAN_TypeDef *CAN) { ENTER_CRITICAL(); @@ -286,7 +264,6 @@ void can_sce(CAN_TypeDef *CAN) { } // ***************************** CAN ***************************** - void process_can(uint8_t can_number) { if (can_number != 0xffU) { @@ -479,4 +456,3 @@ bool can_init(uint8_t can_number) { } return ret; } - diff --git a/panda/board/drivers/fan.h b/panda/board/drivers/fan.h index 2f10e5ca8..c273972a1 100644 --- a/panda/board/drivers/fan.h +++ b/panda/board/drivers/fan.h @@ -1,39 +1,14 @@ +uint16_t fan_tach_counter = 0U; +uint16_t fan_rpm = 0U; + void fan_set_power(uint8_t percentage){ pwm_set(TIM3, 3, percentage); } -uint16_t fan_tach_counter = 0U; -uint16_t fan_rpm = 0U; - // Can be way more acurate than this, but this is probably good enough for our purposes. - // Call this every second void fan_tick(void){ // 4 interrupts per rotation fan_rpm = fan_tach_counter * 15U; fan_tach_counter = 0U; } - -// TACH interrupt handler -void EXTI2_IRQ_Handler(void) { - volatile unsigned int pr = EXTI->PR & (1U << 2); - if ((pr & (1U << 2)) != 0U) { - fan_tach_counter++; - } - EXTI->PR = (1U << 2); -} - -void fan_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); -} \ No newline at end of file diff --git a/panda/board/drivers/gmlan_alt.h b/panda/board/drivers/gmlan_alt.h index c5d111fe6..063ac8502 100644 --- a/panda/board/drivers/gmlan_alt.h +++ b/panda/board/drivers/gmlan_alt.h @@ -288,4 +288,3 @@ bool bitbang_gmlan(CAN_FIFOMailBox_TypeDef *to_bang) { } return gmlan_send_ok; } - diff --git a/panda/board/drivers/llgpio.h b/panda/board/drivers/gpio.h similarity index 83% rename from panda/board/drivers/llgpio.h rename to panda/board/drivers/gpio.h index 0bd58c3b8..77af87658 100644 --- a/panda/board/drivers/llgpio.h +++ b/panda/board/drivers/gpio.h @@ -63,3 +63,13 @@ int get_gpio_input(GPIO_TypeDef *GPIO, unsigned int pin) { return (GPIO->IDR & (1U << pin)) == (1U << pin); } +// Detection with internal pullup +#define PULL_EFFECTIVE_DELAY 4096 +bool detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { + set_gpio_mode(GPIO, pin, MODE_INPUT); + set_gpio_pullup(GPIO, pin, mode); + for (volatile int i=0; iSR != 0) { +void interrupt_timer_handler(void) { + if (INTERRUPT_TIMER->SR != 0) { for(uint16_t i=0U; iSR = 0; + INTERRUPT_TIMER->SR = 0; } void init_interrupts(bool check_rate_limit){ @@ -52,113 +53,6 @@ void init_interrupts(bool check_rate_limit){ interrupts[i].handler = unused_interrupt_handler; } - // Init timer 10 for a 1s interval - register_set_bits(&(RCC->APB1ENR), RCC_APB1ENR_TIM6EN); // Enable interrupt timer peripheral - REGISTER_INTERRUPT(TIM6_DAC_IRQn, TIM6_DAC_IRQ_Handler, 1, FAULT_INTERRUPT_RATE_INTERRUPTS) - register_set(&(TIM6->PSC), (732-1), 0xFFFFU); - register_set(&(TIM6->DIER), TIM_DIER_UIE, 0x5F5FU); - register_set(&(TIM6->CR1), TIM_CR1_CEN, 0x3FU); - TIM6->SR = 0; - NVIC_EnableIRQ(TIM6_DAC_IRQn); + // Init interrupt timer for a 1s interval + interrupt_timer_init(); } - -// ********************* 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 \ No newline at end of file diff --git a/panda/board/drivers/pwm.h b/panda/board/drivers/pwm.h index c3709200c..67e5181e1 100644 --- a/panda/board/drivers/pwm.h +++ b/panda/board/drivers/pwm.h @@ -53,4 +53,4 @@ void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage){ default: break; } -} \ No newline at end of file +} diff --git a/panda/board/drivers/registers.h b/panda/board/drivers/registers.h index 76748295d..4595a5686 100644 --- a/panda/board/drivers/registers.h +++ b/panda/board/drivers/registers.h @@ -8,7 +8,7 @@ typedef struct reg { // 10 bit hash with 23 as a prime #define REGISTER_MAP_SIZE 0x3FFU #define HASHING_PRIME 23U -#define CHECK_COLLISION(hash, addr) (((uint32_t) register_map[hash].address != 0U) && (register_map[hash].address != addr)) +#define CHECK_COLLISION(hash, addr) (((uint32_t) register_map[hash].address != 0U) && (register_map[hash].address != (addr))) reg register_map[REGISTER_MAP_SIZE]; @@ -78,4 +78,4 @@ void init_registers(void) { register_map[i].address = (volatile uint32_t *) 0U; register_map[i].check_mask = 0U; } -} \ No newline at end of file +} diff --git a/panda/board/drivers/rtc.h b/panda/board/drivers/rtc.h index 1e7969603..e8d86fd5d 100644 --- a/panda/board/drivers/rtc.h +++ b/panda/board/drivers/rtc.h @@ -1,5 +1,4 @@ #define RCC_BDCR_OPTIONS (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON) -#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) #define YEAR_OFFSET 2000U @@ -14,95 +13,95 @@ typedef struct __attribute__((packed)) timestamp_t { } timestamp_t; uint8_t to_bcd(uint16_t value){ - return (((value / 10U) & 0x0FU) << 4U) | ((value % 10U) & 0x0FU); + return (((value / 10U) & 0x0FU) << 4U) | ((value % 10U) & 0x0FU); } uint16_t from_bcd(uint8_t value){ - return (((value & 0xF0U) >> 4U) * 10U) + (value & 0x0FU); + return (((value & 0xF0U) >> 4U) * 10U) + (value & 0x0FU); } void rtc_init(void){ - if(board_has_rtc()){ - // Initialize RTC module and clock if not done already. - if((RCC->BDCR & RCC_BDCR_MASK) != RCC_BDCR_OPTIONS){ - puts("Initializing RTC\n"); - // Reset backup domain - register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); + if(current_board->has_rtc){ + // Initialize RTC module and clock if not done already. + if((RCC->BDCR & RCC_BDCR_MASK) != RCC_BDCR_OPTIONS){ + puts("Initializing RTC\n"); + // Reset backup domain + register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - // Disable write protection - register_set_bits(&(PWR->CR), PWR_CR_DBP); + // Disable write protection + disable_bdomain_protection(); - // Clear backup domain reset - register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); + // Clear backup domain reset + register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - // Set RTC options - register_set(&(RCC->BDCR), RCC_BDCR_OPTIONS, RCC_BDCR_MASK); + // Set RTC options + register_set(&(RCC->BDCR), RCC_BDCR_OPTIONS, RCC_BDCR_MASK); - // Enable write protection - register_clear_bits(&(PWR->CR), PWR_CR_DBP); - } + // Enable write protection + enable_bdomain_protection(); } + } } void rtc_set_time(timestamp_t time){ - if(board_has_rtc()){ - puts("Setting RTC time\n"); + if(current_board->has_rtc){ + puts("Setting RTC time\n"); - // Disable write protection - register_set_bits(&(PWR->CR), PWR_CR_DBP); - RTC->WPR = 0xCA; - RTC->WPR = 0x53; + // Disable write protection + disable_bdomain_protection(); + RTC->WPR = 0xCA; + RTC->WPR = 0x53; - // Enable initialization mode - register_set_bits(&(RTC->ISR), RTC_ISR_INIT); - while((RTC->ISR & RTC_ISR_INITF) == 0){} + // Enable initialization mode + register_set_bits(&(RTC->ISR), RTC_ISR_INIT); + while((RTC->ISR & RTC_ISR_INITF) == 0){} - // Set time - RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); - RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); + // Set time + RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); + RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); - // Set options - register_set(&(RTC->CR), 0U, 0xFCFFFFU); + // Set options + register_set(&(RTC->CR), 0U, 0xFCFFFFU); - // Disable initalization mode - register_clear_bits(&(RTC->ISR), RTC_ISR_INIT); + // Disable initalization mode + register_clear_bits(&(RTC->ISR), RTC_ISR_INIT); - // Wait for synchronization - while((RTC->ISR & RTC_ISR_RSF) == 0){} + // Wait for synchronization + while((RTC->ISR & RTC_ISR_RSF) == 0){} - // Re-enable write protection - RTC->WPR = 0x00; - register_clear_bits(&(PWR->CR), PWR_CR_DBP); - } + // Re-enable write protection + RTC->WPR = 0x00; + enable_bdomain_protection(); + } } timestamp_t rtc_get_time(void){ - timestamp_t result; - // Init with zero values in case there is no RTC running - result.year = 0U; - result.month = 0U; - result.day = 0U; - result.weekday = 0U; - result.hour = 0U; - result.minute = 0U; - result.second = 0U; + timestamp_t result; + // Init with zero values in case there is no RTC running + result.year = 0U; + result.month = 0U; + result.day = 0U; + result.weekday = 0U; + result.hour = 0U; + result.minute = 0U; + result.second = 0U; - if(board_has_rtc()){ - // Wait until the register sync flag is set - while((RTC->ISR & RTC_ISR_RSF) == 0){} + if(current_board->has_rtc){ + // Wait until the register sync flag is set + while((RTC->ISR & RTC_ISR_RSF) == 0){} - // Read time and date registers. Since our HSE > 7*LSE, this should be fine. - uint32_t time = RTC->TR; - uint32_t date = RTC->DR; + // Read time and date registers. Since our HSE > 7*LSE, this should be fine. + uint32_t time = RTC->TR; + uint32_t date = RTC->DR; - // Parse values - result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; - result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); - result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); - result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); - result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); - result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); - result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); - } - return result; -} \ No newline at end of file + // Parse values + result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; + result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); + result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); + result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); + result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); + result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); + result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); + } + return result; +} diff --git a/panda/board/drivers/timer.h b/panda/board/drivers/timer.h deleted file mode 100644 index d7aa7e881..000000000 --- a/panda/board/drivers/timer.h +++ /dev/null @@ -1,7 +0,0 @@ -void timer_init(TIM_TypeDef *TIM, int psc) { - register_set(&(TIM->PSC), (psc-1), 0xFFFFU); - register_set(&(TIM->DIER), TIM_DIER_UIE, 0x5F5FU); - register_set(&(TIM->CR1), TIM_CR1_CEN, 0x3FU); - TIM->SR = 0; -} - diff --git a/panda/board/drivers/timers.h b/panda/board/drivers/timers.h new file mode 100644 index 000000000..eb0539886 --- /dev/null +++ b/panda/board/drivers/timers.h @@ -0,0 +1,31 @@ +void timer_init(TIM_TypeDef *TIM, int psc) { + register_set(&(TIM->PSC), (psc-1), 0xFFFFU); + register_set(&(TIM->DIER), TIM_DIER_UIE, 0x5F5FU); + register_set(&(TIM->CR1), TIM_CR1_CEN, 0x3FU); + TIM->SR = 0; +} + +void microsecond_timer_init(void) { + MICROSECOND_TIMER->PSC = (APB1_FREQ)-1U; + MICROSECOND_TIMER->CR1 = TIM_CR1_CEN; + MICROSECOND_TIMER->EGR = TIM_EGR_UG; +} + +uint32_t microsecond_timer_get(void) { + return MICROSECOND_TIMER->CNT; +} + +void interrupt_timer_init(void) { + enable_interrupt_timer(); + REGISTER_INTERRUPT(INTERRUPT_TIMER_IRQ, interrupt_timer_handler, 1, FAULT_INTERRUPT_RATE_INTERRUPTS) + register_set(&(INTERRUPT_TIMER->PSC), ((uint16_t)(15.25*APB1_FREQ)-1U), 0xFFFFU); + register_set(&(INTERRUPT_TIMER->DIER), TIM_DIER_UIE, 0x5F5FU); + register_set(&(INTERRUPT_TIMER->CR1), TIM_CR1_CEN, 0x3FU); + INTERRUPT_TIMER->SR = 0; + NVIC_EnableIRQ(INTERRUPT_TIMER_IRQ); +} + +void tick_timer_init(void) { + timer_init(TICK_TIMER, (uint16_t)((15.25*APB2_FREQ)/8U)); + NVIC_EnableIRQ(TICK_TIMER_IRQ); +} diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index e4f23ead0..af7f99954 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -24,29 +24,20 @@ typedef struct uart_ring { uart_ring uart_ring_##x = { \ .w_ptr_tx = 0, \ .r_ptr_tx = 0, \ - .elems_tx = ((uint8_t *)&elems_tx_##x), \ - .tx_fifo_size = size_tx, \ + .elems_tx = ((uint8_t *)&(elems_tx_##x)), \ + .tx_fifo_size = (size_tx), \ .w_ptr_rx = 0, \ .r_ptr_rx = 0, \ - .elems_rx = ((uint8_t *)&elems_rx_##x), \ - .rx_fifo_size = size_rx, \ - .uart = uart_ptr, \ - .callback = callback_ptr, \ - .dma_rx = rx_dma \ + .elems_rx = ((uint8_t *)&(elems_rx_##x)), \ + .rx_fifo_size = (size_rx), \ + .uart = (uart_ptr), \ + .callback = (callback_ptr), \ + .dma_rx = (rx_dma) \ }; - // ***************************** Function prototypes ***************************** -void uart_init(uart_ring *q, int baud); - -bool getc(uart_ring *q, char *elem); -bool putc(uart_ring *q, char elem); - -void puts(const char *a); -void puth(unsigned int i); -void hexdump(const void *a, int l); - void debug_ring_callback(uart_ring *ring); +void uart_tx_ring(uart_ring *q); // ******************************** UART buffers ******************************** @@ -83,239 +74,7 @@ uart_ring *get_ring_by_number(int a) { return ring; } -// ***************************** 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){ - // Do not read out directly if DMA enabled - if (q->dma_rx == false) { - 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; - // 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(); - } -} - -// This function should be called on: -// * Half-transfer DMA interrupt -// * Full-transfer DMA interrupt -// * UART IDLE detection -uint32_t prev_w_index = 0; -void dma_pointer_handler(uart_ring *q, uint32_t dma_ndtr) { - ENTER_CRITICAL(); - uint32_t w_index = (q->rx_fifo_size - dma_ndtr); - - // Check for new data - if (w_index != prev_w_index){ - // Check for overflow - if ( - ((prev_w_index < q->r_ptr_rx) && (q->r_ptr_rx <= w_index)) || // No rollover - ((w_index < prev_w_index) && ((q->r_ptr_rx <= w_index) || (prev_w_index < q->r_ptr_rx))) // Rollover - ){ - // We lost data. Set the new read pointer to the oldest byte still available - q->r_ptr_rx = (w_index + 1U) % q->rx_fifo_size; - } - - // Set write pointer - q->w_ptr_rx = w_index; - } - - prev_w_index = w_index; - EXIT_CRITICAL(); -} - -// 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 - puts("Encountered UART error: "); puth(err); puts("\n"); - #endif - UART_READ_DR(q->uart) - } - // Send if necessary - uart_tx_ring(q); - - // Run DMA pointer handler if the line is idle - if(q->dma_rx && (status & USART_SR_IDLE)){ - // Reset IDLE flag - UART_READ_DR(q->uart) - - if(q == &uart_ring_gps){ - dma_pointer_handler(&uart_ring_gps, DMA2_Stream5->NDTR); - } else { - #ifdef DEBUG_UART - puts("No IDLE dma_pointer_handler implemented for this UART."); - #endif - } - } - - EXIT_CRITICAL(); -} - -void USART1_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_gps); } -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); } - -void DMA2_Stream5_IRQ_Handler(void) { - ENTER_CRITICAL(); - - // Handle errors - if((DMA2->HISR & DMA_HISR_TEIF5) || (DMA2->HISR & DMA_HISR_DMEIF5) || (DMA2->HISR & DMA_HISR_FEIF5)){ - #ifdef DEBUG_UART - puts("Encountered UART DMA error. Clearing and restarting DMA...\n"); - #endif - - // Clear flags - DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; - - // Re-enable the DMA if necessary - DMA2_Stream5->CR |= DMA_SxCR_EN; - } - - // Re-calculate write pointer and reset flags - dma_pointer_handler(&uart_ring_gps, DMA2_Stream5->NDTR); - DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; - - EXIT_CRITICAL(); -} - -// ***************************** Hardware setup ***************************** - -void dma_rx_init(uart_ring *q) { - // Initialization is UART-dependent - if(q == &uart_ring_gps){ - // DMA2, stream 5, channel 4 - - // Disable FIFO mode (enable direct) - DMA2_Stream5->FCR &= ~DMA_SxFCR_DMDIS; - - // Setup addresses - DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); // Source - DMA2_Stream5->M0AR = (uint32_t)q->elems_rx; // Destination - DMA2_Stream5->NDTR = q->rx_fifo_size; // Number of bytes to copy - - // Circular, Increment memory, byte size, periph -> memory, enable - // Transfer complete, half transfer, transfer error and direct mode error interrupt enable - DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_TEIE | DMA_SxCR_DMEIE | DMA_SxCR_EN; - - // Enable DMA receiver in UART - q->uart->CR3 |= USART_CR3_DMAR; - - // Enable UART IDLE interrupt - q->uart->CR1 |= USART_CR1_IDLEIE; - - // Enable interrupt - NVIC_EnableIRQ(DMA2_Stream5_IRQn); - } else { - puts("Tried to initialize RX DMA for an unsupported UART\n"); - } -} - -#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) { - if (u == USART1) { - // USART1 is on APB2 - u->BRR = __USART_BRR(48000000U, baud); - } else { - u->BRR = __USART_BRR(24000000U, baud); - } -} - -void uart_init(uart_ring *q, int baud) { - // Register interrupts (max data rate: 115200 baud) - if(q->uart == USART1){ - REGISTER_INTERRUPT(USART1_IRQn, USART1_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_1) - } else 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 - } - if(q->dma_rx){ - REGISTER_INTERRUPT(DMA2_Stream5_IRQn, DMA2_Stream5_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_UART_DMA) // Called twice per buffer - } - - // 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 == USART1){ - NVIC_EnableIRQ(USART1_IRQn); - } else 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 - } - - // Initialise RX DMA if used - if(q->dma_rx){ - dma_rx_init(q); - } -} - // ************************* Low-level buffer functions ************************* - bool getc(uart_ring *q, char *elem) { bool ret = false; @@ -427,14 +186,14 @@ void putui(uint32_t i) { } void puth(unsigned int i) { - char c[] = "0123456789abcdef"; + const char c[] = "0123456789abcdef"; for (int pos = 28; pos != -4; pos -= 4) { putch(c[(i >> (unsigned int)(pos)) & 0xFU]); } } void puth2(unsigned int i) { - char c[] = "0123456789abcdef"; + const char c[] = "0123456789abcdef"; for (int pos = 4; pos != -4; pos -= 4) { putch(c[(i >> (unsigned int)(pos)) & 0xFU]); } diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index e85af95af..d08eed2d6 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -38,22 +38,6 @@ void usb_outep3_resume_if_paused(void); // **** supporting defines **** -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 USB_REQ_GET_STATUS 0x00 #define USB_REQ_CLEAR_FEATURE 0x01 #define USB_REQ_SET_FEATURE 0x03 @@ -102,10 +86,6 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; #define STS_SETUP_COMP 4 #define STS_SETUP_UPDT 6 -#define USBD_FS_TRDT_VALUE 5U - -#define USB_OTG_SPEED_FULL 3 - uint8_t resp[MAX_RESP_LEN]; // for the repeating interfaces @@ -143,11 +123,7 @@ uint8_t device_desc[] = { 0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size TOUSBORDER(USB_VID), // idVendor TOUSBORDER(USB_PID), // idProduct -#ifdef STM32F4 0x00, 0x23, // bcdDevice -#else - 0x00, 0x22, // bcdDevice -#endif 0x01, 0x02, // Manufacturer, Product 0x03, 0x01 // Serial Number, Num Configurations }; @@ -410,7 +386,7 @@ void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) { hexdump(src, len); #endif - uint8_t numpacket = (len + (MAX_RESP_LEN - 1U)) / MAX_RESP_LEN; + uint32_t numpacket = (len + (MAX_RESP_LEN - 1U)) / MAX_RESP_LEN; uint32_t count32b = 0; count32b = (len + 3U) / 4U; @@ -420,10 +396,12 @@ void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) { USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); // load the FIFO - const uint32_t *src_copy = (const uint32_t *)src; - for (uint32_t i = 0; i < count32b; i++) { - USBx_DFIFO(ep) = *src_copy; - src_copy++; + if (src != NULL) { + const uint32_t *src_copy = (const uint32_t *)src; + for (uint32_t i = 0; i < count32b; i++) { + USBx_DFIFO(ep) = *src_copy; + src_copy++; + } } } @@ -949,7 +927,7 @@ void usb_irqhandler(void) { //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); } -void usb_outep3_resume_if_paused() { +void usb_outep3_resume_if_paused(void) { ENTER_CRITICAL(); if (!outep3_processing && (USBx_OUTEP(3)->DOEPCTL & USB_OTG_DOEPCTL_NAKSTS) != 0) { USBx_OUTEP(3)->DOEPTSIZ = (1U << 19) | 0x40U; @@ -958,14 +936,6 @@ void usb_outep3_resume_if_paused() { EXIT_CRITICAL(); } -void OTG_FS_IRQ_Handler(void) { - NVIC_DisableIRQ(OTG_FS_IRQn); - //__disable_irq(); - usb_irqhandler(); - //__enable_irq(); - NVIC_EnableIRQ(OTG_FS_IRQn); -} - bool usb_enumerated(void) { // This relies on the USB being suspended after no activity for 3ms. // Seems pretty stable in combination with the EOPF to reject noise. @@ -977,78 +947,3 @@ bool usb_enumerated(void) { usb_eopf_detected = false; return ret; } - -// ***************************** USB init ***************************** - -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); - puts(" resetting PHY\n");*/ - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); - //puts("AHB idle\n"); - - // reset PHY here - USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); - //puts("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); -} \ No newline at end of file diff --git a/panda/board/gpio.h b/panda/board/early_init.h similarity index 65% rename from panda/board/gpio.h rename to panda/board/early_init.h index 01d3b8a3c..0841fc876 100644 --- a/panda/board/gpio.h +++ b/panda/board/early_init.h @@ -1,7 +1,7 @@ // Early bringup -#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef -#define ENTER_SOFTLOADER_MAGIC 0xdeadc0de -#define BOOT_NORMAL 0xdeadb111 +#define ENTER_BOOTLOADER_MAGIC 0xdeadbeefU +#define ENTER_SOFTLOADER_MAGIC 0xdeadc0deU +#define BOOT_NORMAL 0xdeadb111U extern void *g_pfnVectors; extern uint32_t enter_bootloader_mode; @@ -9,7 +9,7 @@ extern uint32_t enter_bootloader_mode; void jump_to_bootloader(void) { // do enter bootloader enter_bootloader_mode = 0; - void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)0x1fff0004)); + void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)BOOTLOADER_ADDRESS)); // jump to bootloader enable_interrupts(); @@ -20,7 +20,7 @@ void jump_to_bootloader(void) { NVIC_SystemReset(); } -void early(void) { +void early_initialization(void) { // Reset global critical depth disable_interrupts(); global_critical_depth = 0; @@ -38,27 +38,17 @@ void early(void) { // if wrong chip, reboot volatile unsigned int id = DBGMCU->IDCODE; - #ifdef STM32F4 - if ((id & 0xFFFU) != 0x463U) { + if ((id & 0xFFFU) != MCU_IDCODE) { enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; } - #else - if ((id & 0xFFFU) != 0x411U) { - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - } - #endif // setup interrupt table SCB->VTOR = (uint32_t)&g_pfnVectors; // early GPIOs float everything - RCC->AHB1ENR = RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | RCC_AHB1ENR_GPIOCEN; + early_gpio_float(); - 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; - - detect_configuration(); + detect_external_debug_serial(); detect_board_type(); if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { diff --git a/panda/board/faults.h b/panda/board/faults.h index 0825586d1..2b152fc1e 100644 --- a/panda/board/faults.h +++ b/panda/board/faults.h @@ -24,7 +24,7 @@ #define FAULT_REGISTER_DIVERGENT (1U << 18) #define FAULT_INTERRUPT_RATE_KLINE_INIT (1U << 19) #define FAULT_INTERRUPT_RATE_CLOCK_SOURCE (1U << 20) -#define FAULT_INTERRUPT_RATE_TIM9 (1U << 21) +#define FAULT_INTERRUPT_RATE_TICK (1U << 21) // Permanent faults #define PERMANENT_FAULTS 0U @@ -49,4 +49,4 @@ void fault_recovered(uint32_t fault) { } else { puts("Cannot recover from a permanent fault!\n"); } -} \ No newline at end of file +} diff --git a/panda/board/libc.h b/panda/board/libc.h index c731dad93..14dde7351 100644 --- a/panda/board/libc.h +++ b/panda/board/libc.h @@ -39,4 +39,3 @@ int memcmp(const void * ptr1, const void * ptr2, unsigned int num) { } return ret; } - diff --git a/panda/board/main.c b/panda/board/main.c index 8337bd169..d9012d80b 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -1,45 +1,21 @@ -//#define EON -//#define PANDA - // ********************* Includes ********************* #include "config.h" -#include "obj/gitversion.h" -#include "main_declarations.h" -#include "critical.h" - -#include "libc.h" -#include "provision.h" -#include "faults.h" - -#include "drivers/registers.h" -#include "drivers/interrupts.h" - -#include "drivers/llcan.h" -#include "drivers/llgpio.h" -#include "drivers/adc.h" #include "drivers/pwm.h" - -#include "board.h" - -#include "drivers/uart.h" #include "drivers/usb.h" #include "drivers/gmlan_alt.h" #include "drivers/kline_init.h" -#include "drivers/timer.h" -#include "drivers/clock.h" -#include "gpio.h" - -#ifndef EON -#include "drivers/spi.h" -#endif +#include "early_init.h" +#include "provision.h" #include "power_saving.h" #include "safety.h" #include "drivers/can.h" +#include "obj/gitversion.h" + extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used // When changing this struct, boardd and python/__init__.py needs to be kept up to date! @@ -127,14 +103,14 @@ void set_safety_mode(uint16_t mode, int16_t param) { switch (mode_copy) { case SAFETY_SILENT: set_intercept_relay(false); - if (board_has_obd()) { + if (current_board->has_obd) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_SILENT; break; case SAFETY_NOOUTPUT: set_intercept_relay(false); - if (board_has_obd()) { + if (current_board->has_obd) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; @@ -143,8 +119,12 @@ void set_safety_mode(uint16_t mode, int16_t param) { set_intercept_relay(false); heartbeat_counter = 0U; heartbeat_lost = false; - if (board_has_obd()) { - current_board->set_can_mode(CAN_MODE_OBD_CAN2); + if (current_board->has_obd) { + if (param == 0) { + current_board->set_can_mode(CAN_MODE_OBD_CAN2); + } else { + current_board->set_can_mode(CAN_MODE_NORMAL); + } } can_silent = ALL_CAN_LIVE; break; @@ -152,7 +132,7 @@ void set_safety_mode(uint16_t mode, int16_t param) { set_intercept_relay(true); heartbeat_counter = 0U; heartbeat_lost = false; - if (board_has_obd()) { + if (current_board->has_obd) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; @@ -161,6 +141,12 @@ void set_safety_mode(uint16_t mode, int16_t param) { can_init_all(); } +bool is_car_safety_mode(uint16_t mode) { + return (mode != SAFETY_SILENT) && + (mode != SAFETY_NOOUTPUT) && + (mode != SAFETY_ELM327); +} + // ***************************** USB port ***************************** int get_health_pkt(void *dat) { @@ -243,13 +229,13 @@ void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) { } } -void usb_cb_ep3_out_complete() { +void usb_cb_ep3_out_complete(void) { if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_BULK_TRANSFER)) { usb_outep3_resume_if_paused(); } } -void usb_cb_enumeration_complete() { +void usb_cb_enumeration_complete(void) { puts("USB enumeration complete\n"); is_enumerated = 1; } @@ -340,7 +326,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) case 0xd0: // addresses are OTP if (setup->b.wValue.w == 1U) { - (void)memcpy(resp, (uint8_t *)0x1fff79c0, 0x10); + (void)memcpy(resp, (uint8_t *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); resp_len = 0x10; } else { get_provision_chunk(resp); @@ -428,7 +414,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; // **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode case 0xdb: - if(board_has_obd()){ + if(current_board->has_obd){ if (setup->b.wValue.w == 1U) { // Enable OBD CAN current_board->set_can_mode(CAN_MODE_OBD_CAN2); @@ -486,9 +472,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) // **** 0xdf: set unsafe mode case 0xdf: // you can only set this if you are in a non car safety mode - if ((current_safety_mode == SAFETY_SILENT) || - (current_safety_mode == SAFETY_NOOUTPUT) || - (current_safety_mode == SAFETY_ELM327)) { + if (!is_car_safety_mode(current_safety_mode)) { unsafe_mode = setup->b.wValue.w; } break; @@ -566,7 +550,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; // **** 0xf0: k-line/l-line wake-up pulse for KWP2000 fast initialization case 0xf0: - if(board_has_lin()) { + if(current_board->has_lin) { bool k = (setup->b.wValue.w == 0U) || (setup->b.wValue.w == 2U); bool l = (setup->b.wValue.w == 1U) || (setup->b.wValue.w == 2U); if (bitbang_wakeup(k, l)) { @@ -601,11 +585,12 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) { heartbeat_counter = 0U; heartbeat_lost = false; + heartbeat_disabled = false; break; } // **** 0xf4: k-line/l-line 5 baud initialization case 0xf4: - if(board_has_lin()) { + if(current_board->has_lin) { bool k = (setup->b.wValue.w == 0U) || (setup->b.wValue.w == 2U); bool l = (setup->b.wValue.w == 1U) || (setup->b.wValue.w == 2U); uint8_t five_baud_addr = (setup->b.wIndex.w & 0xFFU); @@ -626,6 +611,12 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) case 0xf7: green_led_enabled = (setup->b.wValue.w != 0U); break; +#ifdef ALLOW_DEBUG + // **** 0xf8: disable heartbeat checks + case 0xf8: + heartbeat_disabled = true; + break; +#endif default: puts("NO HANDLER "); puth(setup->b.bRequest); @@ -635,43 +626,11 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) return resp_len; } -#ifndef EON -int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { - // data[0] = endpoint - // data[2] = length - // data[4:] = data - UNUSED(len); - int resp_len = 0; - switch (data[0]) { - case 0: - // control transfer - resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), data_out, 0); - break; - case 1: - // ep 1, read - resp_len = usb_cb_ep1_in(data_out, 0x40, 0); - break; - case 2: - // ep 2, send serial - usb_cb_ep2_out(data+4, data[2], 0); - break; - case 3: - // ep 3, send CAN - usb_cb_ep3_out(data+4, data[2], 0); - break; - default: - puts("SPI data invalid"); - break; - } - return resp_len; -} -#endif - // ***************************** main code ***************************** // cppcheck-suppress unusedFunction ; used in headers not included in cppcheck void __initialize_hardware_early(void) { - early(); + early_initialization(); } void __attribute__ ((noinline)) enable_fpu(void) { @@ -679,19 +638,19 @@ void __attribute__ ((noinline)) enable_fpu(void) { SCB->CPACR |= ((3UL << (10U * 2U)) | (3UL << (11U * 2U))); } -// go into SILENT when the EON does not send a heartbeat for this amount of seconds. -#define EON_HEARTBEAT_IGNITION_CNT_ON 5U -#define EON_HEARTBEAT_IGNITION_CNT_OFF 2U +// go into SILENT when heartbeat isn't received for this amount of seconds. +#define HEARTBEAT_IGNITION_CNT_ON 5U +#define HEARTBEAT_IGNITION_CNT_OFF 2U // called at 8Hz uint8_t loop_counter = 0U; -void TIM1_BRK_TIM9_IRQ_Handler(void) { - if (TIM9->SR != 0) { +void tick_handler(void) { + if (TICK_TIMER->SR != 0) { // siren - current_board->set_siren((loop_counter & 1U) && siren_enabled); + current_board->set_siren((loop_counter & 1U) && (siren_enabled || (siren_countdown > 0U))); // decimated to 1Hz - if(loop_counter == 0U){ + if (loop_counter == 0U) { can_live = pending_can_live; current_board->usb_power_mode_tick(uptime_cnt); @@ -724,39 +683,49 @@ void TIM1_BRK_TIM9_IRQ_Handler(void) { heartbeat_counter += 1U; } - #ifdef EON - // check heartbeat counter if we are running EON code. - // if the heartbeat has been gone for a while, go to SILENT safety mode and enter power save - if (heartbeat_counter >= (check_started() ? EON_HEARTBEAT_IGNITION_CNT_ON : EON_HEARTBEAT_IGNITION_CNT_OFF)) { - puts("EON hasn't sent a heartbeat for 0x"); - puth(heartbeat_counter); - puts(" seconds. Safety is set to SILENT mode.\n"); - if (current_safety_mode != SAFETY_SILENT) { - set_safety_mode(SAFETY_SILENT, 0U); - } - if (power_save_status != POWER_SAVE_STATUS_ENABLED) { - set_power_save_state(POWER_SAVE_STATUS_ENABLED); - } - - // set flag to indicate the heartbeat was lost - heartbeat_lost = true; - - // Also disable IR when the heartbeat goes missing - current_board->set_ir_power(0U); - - // If enumerated but no heartbeat (phone up, boardd not running), turn the fan on to cool the device - if(usb_enumerated()){ - current_board->set_fan_power(50U); - } else { - current_board->set_fan_power(0U); - } + if (siren_countdown > 0U) { + siren_countdown -= 1U; } - // enter CDP mode when car starts to ensure we are charging a turned off EON - if (check_started() && (usb_power_mode != USB_POWER_CDP)) { - current_board->set_usb_power_mode(USB_POWER_CDP); + if (!heartbeat_disabled) { + // if the heartbeat has been gone for a while, go to SILENT safety mode and enter power save + if (heartbeat_counter >= (check_started() ? HEARTBEAT_IGNITION_CNT_ON : HEARTBEAT_IGNITION_CNT_OFF)) { + puts("device hasn't sent a heartbeat for 0x"); + puth(heartbeat_counter); + puts(" seconds. Safety is set to SILENT mode.\n"); + + if (controls_allowed) { + siren_countdown = 5U; + } + + // set flag to indicate the heartbeat was lost + if (is_car_safety_mode(current_safety_mode)) { + heartbeat_lost = true; + } + + if (current_safety_mode != SAFETY_SILENT) { + set_safety_mode(SAFETY_SILENT, 0U); + } + if (power_save_status != POWER_SAVE_STATUS_ENABLED) { + set_power_save_state(POWER_SAVE_STATUS_ENABLED); + } + + // Also disable IR when the heartbeat goes missing + current_board->set_ir_power(0U); + + // If enumerated but no heartbeat (phone up, boardd not running), turn the fan on to cool the device + if(usb_enumerated()){ + current_board->set_fan_power(50U); + } else { + current_board->set_fan_power(0U); + } + } + + // enter CDP mode when car starts to ensure we are charging a turned off EON + if (check_started() && (usb_power_mode != USB_POWER_CDP)) { + current_board->set_usb_power_mode(USB_POWER_CDP); + } } - #endif // check registers check_registers(); @@ -764,7 +733,7 @@ void TIM1_BRK_TIM9_IRQ_Handler(void) { // set ignition_can to false after 2s of no CAN seen if (ignition_can_cnt > 2U) { ignition_can = false; - }; + } // on to the next one uptime_cnt += 1U; @@ -778,24 +747,21 @@ void TIM1_BRK_TIM9_IRQ_Handler(void) { loop_counter++; loop_counter %= 8U; } - TIM9->SR = 0; + TICK_TIMER->SR = 0; } -#define MAX_FADE 8192U + int main(void) { // Init interrupt table init_interrupts(true); - // 8Hz timer - REGISTER_INTERRUPT(TIM1_BRK_TIM9_IRQn, TIM1_BRK_TIM9_IRQ_Handler, 10U, FAULT_INTERRUPT_RATE_TIM9) - // shouldn't have interrupts here, but just in case disable_interrupts(); // init early devices clock_init(); peripherals_init(); - detect_configuration(); + detect_external_debug_serial(); detect_board_type(); adc_init(); @@ -825,14 +791,14 @@ int main(void) { uart_init(&uart_ring_debug, 115200); } - if (board_has_gps()) { + if (current_board->has_gps) { uart_init(&uart_ring_gps, 9600); } else { // enable ESP uart uart_init(&uart_ring_gps, 115200); } - if(board_has_lin()){ + if(current_board->has_lin){ // enable LIN uart_init(&uart_ring_lin1, 10400); UART5->CR2 |= USART_CR2_LINEN; @@ -840,13 +806,7 @@ int main(void) { USART3->CR2 |= USART_CR2_LINEN; } - // init microsecond system timer - // increments 1000000 times per second - // generate an update to set the prescaler - TIM2->PSC = 48-1; - TIM2->CR1 = TIM_CR1_CEN; - TIM2->EGR = TIM_EGR_UG; - // use TIM2->CNT to read + microsecond_timer_init(); // init to SILENT and can silent set_safety_mode(SAFETY_SILENT, 0); @@ -854,13 +814,9 @@ int main(void) { // enable CAN TXs current_board->enable_can_transceivers(true); -#ifndef EON - spi_init(); -#endif - - // 8hz - timer_init(TIM9, 183); - NVIC_EnableIRQ(TIM1_BRK_TIM9_IRQn); + // 8Hz timer + REGISTER_INTERRUPT(TICK_TIMER_IRQ, tick_handler, 10U, FAULT_INTERRUPT_RATE_TICK) + tick_timer_init(); #ifdef DEBUG puts("DEBUG ENABLED\n"); @@ -882,18 +838,18 @@ int main(void) { uint32_t div_mode = ((usb_power_mode == USB_POWER_DCP) ? 4U : 1U); // useful for debugging, fade breaks = panda is overloaded - for(uint32_t fade = 0U; fade < MAX_FADE; fade += div_mode){ + for(uint32_t fade = 0U; fade < MAX_LED_FADE; fade += div_mode){ current_board->set_led(LED_RED, true); delay(fade >> 4); current_board->set_led(LED_RED, false); - delay((MAX_FADE - fade) >> 4); + delay((MAX_LED_FADE - fade) >> 4); } - for(uint32_t fade = MAX_FADE; fade > 0U; fade -= div_mode){ + for(uint32_t fade = MAX_LED_FADE; fade > 0U; fade -= div_mode){ current_board->set_led(LED_RED, true); delay(fade >> 4); current_board->set_led(LED_RED, false); - delay((MAX_FADE - fade) >> 4); + delay((MAX_LED_FADE - fade) >> 4); } #ifdef DEBUG_FAULTS diff --git a/panda/board/main_declarations.h b/panda/board/main_declarations.h index 8181d6e32..cb86eb7a6 100644 --- a/panda/board/main_declarations.h +++ b/panda/board/main_declarations.h @@ -5,7 +5,8 @@ void puth2(unsigned int i); typedef struct board board; typedef struct harness_configuration harness_configuration; void can_flip_buses(uint8_t bus1, uint8_t bus2); -void can_set_obd(uint8_t harness_orientation, bool obd); +void pwm_init(TIM_TypeDef *TIM, uint8_t channel); +void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage); // ********************* Globals ********************** uint8_t hw_type = 0; @@ -14,5 +15,7 @@ bool is_enumerated = 0; uint32_t heartbeat_counter = 0; uint32_t uptime_cnt = 0; bool heartbeat_lost = false; +bool heartbeat_disabled = false; bool siren_enabled = false; +uint32_t siren_countdown = 0; bool green_led_enabled = false; diff --git a/panda/board/pedal/main.c b/panda/board/pedal/main.c index 3d7bd03a2..32d85aab3 100644 --- a/panda/board/pedal/main.c +++ b/panda/board/pedal/main.c @@ -1,32 +1,13 @@ // ********************* Includes ********************* +//#define PEDAL_USB #include "../config.h" -#include "libc.h" -#include "main_declarations.h" -#include "critical.h" -#include "faults.h" - -#include "drivers/registers.h" -#include "drivers/interrupts.h" -#include "drivers/llcan.h" -#include "drivers/llgpio.h" -#include "drivers/adc.h" - -#include "board.h" - -#include "drivers/clock.h" -#include "drivers/dac.h" -#include "drivers/timer.h" - -#include "gpio.h" +#include "early_init.h" #include "crc.h" #define CAN CAN1 -//#define PEDAL_USB - #ifdef PEDAL_USB - #include "drivers/uart.h" #include "drivers/usb.h" #else // no serial either @@ -41,12 +22,12 @@ } #endif -#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef +#define ENTER_BOOTLOADER_MAGIC 0xdeadbeefU uint32_t enter_bootloader_mode; // cppcheck-suppress unusedFunction ; used in headers not included in cppcheck void __initialize_hardware_early(void) { - early(); + early_initialization(); } // ********************* serial debugging ********************* @@ -84,6 +65,11 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) unsigned int resp_len = 0; uart_ring *ur = NULL; switch (setup->b.bRequest) { + // **** 0xc1: get hardware type + case 0xc1: + resp[0] = hw_type; + resp_len = 1; + break; // **** 0xe0: uart read case 0xe0: ur = get_ring_by_number(setup->b.wValue.w); @@ -136,8 +122,7 @@ uint32_t current_index = 0; #define FAULT_TIMEOUT 5U #define FAULT_INVALID 6U uint8_t state = FAULT_STARTUP; - -const uint8_t crc_poly = 0xD5; // standard crc8 +const uint8_t crc_poly = 0xD5U; // standard crc8 void CAN1_RX0_IRQ_Handler(void) { while ((CAN->RF0R & CAN_RF0R_FMP0) != 0) { @@ -286,7 +271,7 @@ int main(void) { REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - + // Should run at around 732Hz (see init below) REGISTER_INTERRUPT(TIM3_IRQn, TIM3_IRQ_Handler, 1000U, FAULT_INTERRUPT_RATE_TIM3) @@ -295,7 +280,7 @@ int main(void) { // init devices clock_init(); peripherals_init(); - detect_configuration(); + detect_external_debug_serial(); detect_board_type(); // init board diff --git a/panda/board/pedal/main_declarations.h b/panda/board/pedal/main_declarations.h index 9a40f8ae3..2f2fe6fee 100644 --- a/panda/board/pedal/main_declarations.h +++ b/panda/board/pedal/main_declarations.h @@ -8,4 +8,4 @@ typedef struct harness_configuration harness_configuration; // ********************* Globals ********************** uint8_t hw_type = 0; const board *current_board; -bool is_enumerated = 0; \ No newline at end of file +bool is_enumerated = 0; diff --git a/panda/board/power_saving.h b/panda/board/power_saving.h index 2cb79cb61..52c65028a 100644 --- a/panda/board/power_saving.h +++ b/panda/board/power_saving.h @@ -13,15 +13,15 @@ void set_power_save_state(int state) { bool enable = false; if (state == POWER_SAVE_STATUS_ENABLED) { puts("enable power savings\n"); - if (board_has_gps()) { - char UBLOX_SLEEP_MSG[] = "\xb5\x62\x06\x04\x04\x00\x01\x00\x08\x00\x17\x78"; + if (current_board->has_gps) { + const char UBLOX_SLEEP_MSG[] = "\xb5\x62\x06\x04\x04\x00\x01\x00\x08\x00\x17\x78"; uart_ring *ur = get_ring_by_number(1); for (unsigned int i = 0; i < sizeof(UBLOX_SLEEP_MSG) - 1U; i++) while (!putc(ur, UBLOX_SLEEP_MSG[i])); } } else { puts("disable power savings\n"); - if (board_has_gps()) { - char UBLOX_WAKE_MSG[] = "\xb5\x62\x06\x04\x04\x00\x01\x00\x09\x00\x18\x7a"; + if (current_board->has_gps) { + const char UBLOX_WAKE_MSG[] = "\xb5\x62\x06\x04\x04\x00\x01\x00\x09\x00\x18\x7a"; uart_ring *ur = get_ring_by_number(1); for (unsigned int i = 0; i < sizeof(UBLOX_WAKE_MSG) - 1U; i++) while (!putc(ur, UBLOX_WAKE_MSG[i])); } @@ -37,13 +37,13 @@ void set_power_save_state(int state) { current_board->set_gps_mode(GPS_DISABLED); } - if(board_has_gmlan()){ + if(current_board->has_hw_gmlan){ // turn on GMLAN set_gpio_output(GPIOB, 14, enable); set_gpio_output(GPIOB, 15, enable); } - if(board_has_lin()){ + if(current_board->has_lin){ // turn on LIN set_gpio_output(GPIOB, 7, enable); set_gpio_output(GPIOA, 14, enable); diff --git a/panda/board/provision.h b/panda/board/provision.h index 0b09d8ff8..ed670a6db 100644 --- a/panda/board/provision.h +++ b/panda/board/provision.h @@ -5,7 +5,7 @@ // SHA1 checksum = 0x1C - 0x20 void get_provision_chunk(uint8_t *resp) { - (void)memcpy(resp, (uint8_t *)0x1fff79e0, PROVISION_CHUNK_LEN); + (void)memcpy(resp, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); if (memcmp(resp, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) == 0) { (void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20); } @@ -13,7 +13,6 @@ void get_provision_chunk(uint8_t *resp) { uint8_t chunk[PROVISION_CHUNK_LEN]; bool is_provisioned(void) { - (void)memcpy(chunk, (uint8_t *)0x1fff79e0, PROVISION_CHUNK_LEN); + (void)memcpy(chunk, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); return (memcmp(chunk, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) != 0); } - diff --git a/panda/board/safety.h b/panda/board/safety.h index a3aa6bc1a..fd20cf374 100644 --- a/panda/board/safety.h +++ b/panda/board/safety.h @@ -127,7 +127,7 @@ int get_addr_check_index(CAN_FIFOMailBox_TypeDef *to_push, AddrCheckStruct addr_ // 1Hz safety function called by main. Now just a check for lagging safety messages void safety_tick(const safety_hooks *hooks) { - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); if (hooks->addr_check != NULL) { for (int i=0; i < hooks->addr_check_len; i++) { uint32_t elapsed_time = get_ts_elapsed(ts, hooks->addr_check[i].last_timestamp); @@ -165,7 +165,7 @@ bool is_msg_valid(AddrCheckStruct addr_list[], int index) { void update_addr_timestamp(AddrCheckStruct addr_list[], int index) { if (index != -1) { - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); addr_list[index].last_timestamp = ts; } } @@ -251,10 +251,10 @@ const safety_hook_config safety_hook_registry[] = { {SAFETY_NOOUTPUT, &nooutput_hooks}, {SAFETY_HYUNDAI_LEGACY, &hyundai_legacy_hooks}, #ifdef ALLOW_DEBUG + {SAFETY_TESLA, &tesla_hooks}, {SAFETY_MAZDA, &mazda_hooks}, {SAFETY_SUBARU_LEGACY, &subaru_legacy_hooks}, {SAFETY_VOLKSWAGEN_PQ, &volkswagen_pq_hooks}, - {SAFETY_TESLA, &tesla_hooks}, {SAFETY_ALLOUTPUT, &alloutput_hooks}, {SAFETY_GM_ASCM, &gm_ascm_hooks}, {SAFETY_FORD, &ford_hooks}, diff --git a/panda/board/safety/safety_chrysler.h b/panda/board/safety/safety_chrysler.h index 044485cb6..7287fa1cb 100644 --- a/panda/board/safety/safety_chrysler.h +++ b/panda/board/safety/safety_chrysler.h @@ -9,11 +9,11 @@ const int CHRYSLER_STANDSTILL_THRSLD = 10; // about 1m/s const CanMsg CHRYSLER_TX_MSGS[] = {{571, 0, 3}, {658, 0, 6}, {678, 0, 8}}; AddrCheckStruct chrysler_rx_checks[] = { - {.msg = {{544, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}}}, - {.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}}}, - {.msg = {{500, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{308, 0, 8, .check_checksum = false, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{320, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, + {.msg = {{544, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{500, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{308, 0, 8, .check_checksum = false, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{320, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, }; const int CHRYSLER_RX_CHECK_LEN = sizeof(chrysler_rx_checks) / sizeof(chrysler_rx_checks[0]); @@ -25,10 +25,10 @@ static uint8_t chrysler_get_checksum(CAN_FIFOMailBox_TypeDef *to_push) { static uint8_t chrysler_compute_checksum(CAN_FIFOMailBox_TypeDef *to_push) { /* This function does not want the checksum byte in the input data. jeep chrysler canbus checksum from http://illmatics.com/Remote%20Car%20Hacking.pdf */ - uint8_t checksum = 0xFF; + uint8_t checksum = 0xFFU; int len = GET_LEN(to_push); for (int j = 0; j < (len - 1); j++) { - uint8_t shift = 0x80; + uint8_t shift = 0x80U; uint8_t curr = (uint8_t)GET_BYTE(to_push, j); for (int i=0; i<8; i++) { uint8_t bit_sum = curr & shift; @@ -132,7 +132,7 @@ static int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // LKA STEER if (addr == 0x292) { int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1) - 1024U; - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); bool violation = 0; if (controls_allowed) { diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h index a39c4125c..e6655c3d4 100644 --- a/panda/board/safety/safety_elm327.h +++ b/panda/board/safety/safety_elm327.h @@ -33,6 +33,7 @@ static int elm327_tx_lin_hook(int lin_num, uint8_t *data, int len) { return tx; } +// If current_board->has_obd and safety_param == 0, bus 1 is multiplexed to the OBD-II port const safety_hooks elm327_hooks = { .init = nooutput_init, .rx = default_rx_hook, diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h index 0e9624ddc..111597e5b 100644 --- a/panda/board/safety/safety_gm.h +++ b/panda/board/safety/safety_gm.h @@ -24,12 +24,13 @@ const CanMsg GM_TX_MSGS[] = {{384, 0, 4}, {1033, 0, 7}, {1034, 0, 7}, {715, 0, 8 {0x104c006c, 3, 3}, {0x10400060, 3, 5}}; // gmlan // TODO: do checksum and counter checks. Add correct timestep, 0.1s for now. + AddrCheckStruct gm_rx_checks[] = { - {.msg = {{388, 0, 8, .expected_timestep = 100000U}}}, - {.msg = {{842, 0, 5, .expected_timestep = 100000U}}}, - {.msg = {{481, 0, 7, .expected_timestep = 100000U}}}, - {.msg = {{241, 0, 6, .expected_timestep = 100000U}}}, - {.msg = {{417, 0, 7, .expected_timestep = 100000U}}}, + {.msg = {{388, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + {.msg = {{842, 0, 5, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + {.msg = {{481, 0, 7, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + {.msg = {{241, 0, 6, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + {.msg = {{417, 0, 7, .expected_timestep = 100000U}, { 0 }, { 0 }}}, }; const int GM_RX_CHECK_LEN = sizeof(gm_rx_checks) / sizeof(gm_rx_checks[0]); @@ -143,7 +144,7 @@ static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // LKA STEER: safety check if (addr == 384) { int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1); - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); bool violation = 0; desired_torque = to_signed(desired_torque, 11); diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h index 1d851dc67..0e2acdb46 100644 --- a/panda/board/safety/safety_honda.h +++ b/panda/board/safety/safety_honda.h @@ -27,18 +27,18 @@ const int HONDA_BOSCH_ACCEL_MIN = -350; // max braking == -3.5m/s2 // Nidec and Bosch giraffe have pt on bus 0 AddrCheckStruct honda_rx_checks[] = { {.msg = {{0x1A6, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, - {0x296, 0, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}}}, - {.msg = {{0x158, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}}}, - {.msg = {{0x17C, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}}}, + {0x296, 0, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U},{ 0 }}}, + {.msg = {{0x158, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{0x17C, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, }; const int HONDA_RX_CHECKS_LEN = sizeof(honda_rx_checks) / sizeof(honda_rx_checks[0]); // Bosch harness has pt on bus 1 AddrCheckStruct honda_bh_rx_checks[] = { - {.msg = {{0x296, 1, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}}}, - {.msg = {{0x158, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}}}, + {.msg = {{0x296, 1, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, { 0 }, { 0 }}}, + {.msg = {{0x158, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, {.msg = {{0x17C, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, - {0x1BE, 1, 3, .check_checksum = true, .max_counter = 3U, .expected_timestep = 20000U}}}, + {0x1BE, 1, 3, .check_checksum = true, .max_counter = 3U, .expected_timestep = 20000U}, { 0 }}}, }; const int HONDA_BH_RX_CHECKS_LEN = sizeof(honda_bh_rx_checks) / sizeof(honda_bh_rx_checks[0]); @@ -161,16 +161,25 @@ static int honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { } } - // if steering controls messages are received on the destination bus, it's an indication - // that the relay might be malfunctioning bool stock_ecu_detected = false; int bus_rdr_car = (honda_hw == HONDA_BH_HW) ? 0 : 2; // radar bus, car side - if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && ((addr == 0xE4) || (addr == 0x194))) { - if (((honda_hw != HONDA_N_HW) && (bus == bus_rdr_car)) || - ((honda_hw == HONDA_N_HW) && (bus == 0))) { + int pt_bus = (honda_hw == HONDA_BH_HW) ? 1 : 0; + + if (safety_mode_cnt > RELAY_TRNS_TIMEOUT) { + // If steering controls messages are received on the destination bus, it's an indication + // that the relay might be malfunctioning + if ((addr == 0xE4) || (addr == 0x194)) { + if (((honda_hw != HONDA_N_HW) && (bus == bus_rdr_car)) || ((honda_hw == HONDA_N_HW) && (bus == 0))) { + stock_ecu_detected = true; + } + } + // If Honda Bosch longitudinal mode is selected we need to ensure the radar is turned off + // Verify this by ensuring ACC_CONTROL (0x1DF) is not received on the PT bus + if (honda_bosch_long && (bus == pt_bus) && (addr == 0x1DF)) { stock_ecu_detected = true; } } + generic_rx_checks(stock_ecu_detected); } return valid; @@ -290,6 +299,13 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { } } + // Only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address + if (addr == 0x18DAB0F1) { + if ((GET_BYTES_04(to_send) != 0x00803E02) || (GET_BYTES_48(to_send) != 0x0)) { + tx = 0; + } + } + // 1 allows the message through return tx; } diff --git a/panda/board/safety/safety_hyundai.h b/panda/board/safety/safety_hyundai.h index 39966e0dc..e39793786 100644 --- a/panda/board/safety/safety_hyundai.h +++ b/panda/board/safety/safety_hyundai.h @@ -18,24 +18,30 @@ const CanMsg HYUNDAI_TX_MSGS[] = { }; AddrCheckStruct hyundai_rx_checks[] = { - {.msg = {{608, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}}}, - {.msg = {{902, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}}}, - {.msg = {{916, 0, 8, .check_checksum = true, .max_counter = 7U, .expected_timestep = 10000U}}}, - {.msg = {{1057, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, + {.msg = {{608, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, + {881, 0, 8, .expected_timestep = 10000U}, { 0 }}}, + {.msg = {{902, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{916, 0, 8, .check_checksum = true, .max_counter = 7U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{1057, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, }; const int HYUNDAI_RX_CHECK_LEN = sizeof(hyundai_rx_checks) / sizeof(hyundai_rx_checks[0]); // older hyundai models have less checks due to missing counters and checksums AddrCheckStruct hyundai_legacy_rx_checks[] = { {.msg = {{608, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, - {881, 0, 8, .expected_timestep = 10000U}}}, - {.msg = {{902, 0, 8, .expected_timestep = 10000U}}}, - {.msg = {{916, 0, 8, .expected_timestep = 10000U}}}, - {.msg = {{1057, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, + {881, 0, 8, .expected_timestep = 10000U}, { 0 }}}, + {.msg = {{902, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{916, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{1057, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, }; const int HYUNDAI_LEGACY_RX_CHECK_LEN = sizeof(hyundai_legacy_rx_checks) / sizeof(hyundai_legacy_rx_checks[0]); +const int HYUNDAI_PARAM_EV_GAS = 1; +const int HYUNDAI_PARAM_HYBRID_GAS = 2; + bool hyundai_legacy = false; +bool hyundai_ev_gas_signal = false; +bool hyundai_hybrid_gas_signal = false; static uint8_t hyundai_get_counter(CAN_FIFOMailBox_TypeDef *to_push) { int addr = GET_ADDR(to_push); @@ -145,12 +151,14 @@ static int hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { cruise_engaged_prev = cruise_engaged; } - if ((addr == 608) || (hyundai_legacy && (addr == 881))) { - if (addr == 608) { - gas_pressed = (GET_BYTE(to_push, 7) >> 6) != 0; - } else { - gas_pressed = (((GET_BYTE(to_push, 4) & 0x7F) << 1) | GET_BYTE(to_push, 3) >> 7) != 0; - } + // read gas pressed signal + if ((addr == 881) && hyundai_ev_gas_signal) { + gas_pressed = (((GET_BYTE(to_push, 4) & 0x7F) << 1) | GET_BYTE(to_push, 3) >> 7) != 0; + } else if ((addr == 881) && hyundai_hybrid_gas_signal) { + gas_pressed = GET_BYTE(to_push, 7) != 0; + } else if (addr == 608) { // ICE + gas_pressed = (GET_BYTE(to_push, 7) >> 6) != 0; + } else { } // sample wheel speed, averaging opposite corners @@ -186,7 +194,7 @@ static int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // LKA STEER: safety check if (addr == 832) { int desired_torque = ((GET_BYTES_04(to_send) >> 16) & 0x7ff) - 1024; - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); bool violation = 0; if (controls_allowed) { @@ -260,19 +268,21 @@ static int hyundai_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { } static void hyundai_init(int16_t param) { - UNUSED(param); controls_allowed = false; relay_malfunction_reset(); hyundai_legacy = false; + hyundai_ev_gas_signal = GET_FLAG(param, HYUNDAI_PARAM_EV_GAS); + hyundai_hybrid_gas_signal = !hyundai_ev_gas_signal && GET_FLAG(param, HYUNDAI_PARAM_HYBRID_GAS); } static void hyundai_legacy_init(int16_t param) { - UNUSED(param); controls_allowed = false; relay_malfunction_reset(); hyundai_legacy = true; + hyundai_ev_gas_signal = GET_FLAG(param, HYUNDAI_PARAM_EV_GAS); + hyundai_hybrid_gas_signal = !hyundai_ev_gas_signal && GET_FLAG(param, HYUNDAI_PARAM_HYBRID_GAS); } const safety_hooks hyundai_hooks = { diff --git a/panda/board/safety/safety_mazda.h b/panda/board/safety/safety_mazda.h index 12e924040..8be1c36bf 100644 --- a/panda/board/safety/safety_mazda.h +++ b/panda/board/safety/safety_mazda.h @@ -31,11 +31,11 @@ const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8}, {MAZDA_CRZ_BTNS, 0, 8}}; bool mazda_lkas_allowed = false; AddrCheckStruct mazda_rx_checks[] = { - {.msg = {{MAZDA_CRZ_CTRL, 0, 8, .expected_timestep = 20000U}}}, - {.msg = {{MAZDA_CRZ_BTNS, 0, 8, .expected_timestep = 100000U}}}, - {.msg = {{MAZDA_STEER_TORQUE, 0, 8, .expected_timestep = 12000U}}}, - {.msg = {{MAZDA_ENGINE_DATA, 0, 8, .expected_timestep = 10000U}}}, - {.msg = {{MAZDA_PEDALS, 0, 8, .expected_timestep = 20000U}}}, + {.msg = {{MAZDA_CRZ_CTRL, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_CRZ_BTNS, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_STEER_TORQUE, 0, 8, .expected_timestep = 12000U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_ENGINE_DATA, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_PEDALS, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, }; const int MAZDA_RX_CHECKS_LEN = sizeof(mazda_rx_checks) / sizeof(mazda_rx_checks[0]); @@ -120,7 +120,7 @@ static int mazda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { if (addr == MAZDA_LKAS) { int desired_torque = (((GET_BYTE(to_send, 0) & 0x0f) << 8) | GET_BYTE(to_send, 1)) - MAZDA_MAX_STEER; bool violation = 0; - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); if (controls_allowed) { diff --git a/panda/board/safety/safety_nissan.h b/panda/board/safety/safety_nissan.h index ca0f54e53..91b3c6933 100644 --- a/panda/board/safety/safety_nissan.h +++ b/panda/board/safety/safety_nissan.h @@ -16,11 +16,11 @@ const CanMsg NISSAN_TX_MSGS[] = {{0x169, 0, 8}, {0x2b1, 0, 8}, {0x4cc, 0, 8}, {0 // Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model. AddrCheckStruct nissan_rx_checks[] = { {.msg = {{0x2, 0, 5, .expected_timestep = 10000U}, - {0x2, 1, 5, .expected_timestep = 10000U}}}, // STEER_ANGLE_SENSOR (100Hz) + {0x2, 1, 5, .expected_timestep = 10000U}, { 0 }}}, // STEER_ANGLE_SENSOR (100Hz) {.msg = {{0x285, 0, 8, .expected_timestep = 20000U}, - {0x285, 1, 8, .expected_timestep = 20000U}}}, // WHEEL_SPEEDS_REAR (50Hz) + {0x285, 1, 8, .expected_timestep = 20000U}, { 0 }}}, // WHEEL_SPEEDS_REAR (50Hz) {.msg = {{0x30f, 2, 3, .expected_timestep = 100000U}, - {0x30f, 1, 3, .expected_timestep = 100000U}}}, // CRUISE_STATE (10Hz) + {0x30f, 1, 3, .expected_timestep = 100000U}, { 0 }}}, // CRUISE_STATE (10Hz) {.msg = {{0x15c, 0, 8, .expected_timestep = 20000U}, {0x15c, 1, 8, .expected_timestep = 20000U}, {0x239, 0, 8, .expected_timestep = 20000U}}}, // GAS_PEDAL (100Hz / 50Hz) diff --git a/panda/board/safety/safety_subaru.h b/panda/board/safety/safety_subaru.h index b2e8c0738..93b7f28dd 100644 --- a/panda/board/safety/safety_subaru.h +++ b/panda/board/safety/safety_subaru.h @@ -16,11 +16,11 @@ const CanMsg SUBARU_TX_MSGS[] = {{0x122, 0, 8}, {0x221, 0, 8}, {0x322, 0, 8}}; const int SUBARU_TX_MSGS_LEN = sizeof(SUBARU_TX_MSGS) / sizeof(SUBARU_TX_MSGS[0]); AddrCheckStruct subaru_rx_checks[] = { - {.msg = {{ 0x40, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}}}, - {.msg = {{0x119, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{0x139, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{0x13a, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{0x240, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 50000U}}}, + {.msg = {{ 0x40, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{0x119, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{0x139, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{0x13a, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{0x240, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 50000U}, { 0 }, { 0 }}}, }; const int SUBARU_RX_CHECK_LEN = sizeof(subaru_rx_checks) / sizeof(subaru_rx_checks[0]); @@ -29,9 +29,9 @@ const int SUBARU_L_TX_MSGS_LEN = sizeof(SUBARU_L_TX_MSGS) / sizeof(SUBARU_L_TX_M // TODO: do checksum and counter checks after adding the signals to the outback dbc file AddrCheckStruct subaru_l_rx_checks[] = { - {.msg = {{0x140, 0, 8, .expected_timestep = 10000U}}}, - {.msg = {{0x371, 0, 8, .expected_timestep = 20000U}}}, - {.msg = {{0x144, 0, 8, .expected_timestep = 50000U}}}, + {.msg = {{0x140, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{0x371, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{0x144, 0, 8, .expected_timestep = 50000U}, { 0 }, { 0 }}}, }; const int SUBARU_L_RX_CHECK_LEN = sizeof(subaru_l_rx_checks) / sizeof(subaru_l_rx_checks[0]); @@ -163,7 +163,7 @@ static int subaru_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { if (addr == 0x122) { int desired_torque = ((GET_BYTES_04(to_send) >> 16) & 0x1FFF); bool violation = 0; - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); desired_torque = -1 * to_signed(desired_torque, 13); @@ -227,7 +227,7 @@ static int subaru_legacy_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { if (addr == 0x164) { int desired_torque = ((GET_BYTES_04(to_send) >> 8) & 0x1FFF); bool violation = 0; - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); desired_torque = -1 * to_signed(desired_torque, 13); diff --git a/panda/board/safety/safety_tesla.h b/panda/board/safety/safety_tesla.h index 78b80e3bc..a5e1ba5e4 100644 --- a/panda/board/safety/safety_tesla.h +++ b/panda/board/safety/safety_tesla.h @@ -1,18 +1,3 @@ -// board enforces -// in-state -// accel set/resume -// out-state -// cancel button -// regen paddle -// accel rising edge -// brake rising edge -// brake > 0mph -// -bool fmax_limit_check(float val, const float MAX_VAL, const float MIN_VAL) { - return (val > MAX_VAL) || (val < MIN_VAL); -} - -// 2m/s are added to be less restrictive const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_UP = { {2., 7., 17.}, {5., .8, .25}}; @@ -21,186 +6,193 @@ const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_DOWN = { {2., 7., 17.}, {5., 3.5, .8}}; -const struct lookup_t TESLA_LOOKUP_MAX_ANGLE = { - {2., 29., 38.}, - {410., 92., 36.}}; +const int TESLA_DEG_TO_CAN = 10; -const uint32_t TESLA_RT_INTERVAL = 250000; // 250ms between real time checks +const CanMsg TESLA_TX_MSGS[] = { + {0x488, 0, 4}, // DAS_steeringControl + {0x45, 0, 8}, // STW_ACTN_RQ + {0x45, 2, 8}, // STW_ACTN_RQ +}; -// state of angle limits -float tesla_desired_angle_last = 0; // last desired steer angle -float tesla_rt_angle_last = 0.; // last real time angle -float tesla_ts_angle_last = 0; - -int tesla_controls_allowed_last = 0; - -int tesla_speed = 0; -int eac_status = 0; - -void set_gmlan_digital_output(int to_set); -void reset_gmlan_switch_timeout(void); -void gmlan_switch_init(int timeout_enable); +AddrCheckStruct tesla_rx_checks[] = { + {.msg = {{0x370, 0, 8, .expected_timestep = 40000U}, { 0 }, { 0 }}}, // EPAS_sysStatus (25Hz) + {.msg = {{0x108, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque1 (100Hz) + {.msg = {{0x118, 0, 6, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque2 (100Hz) + {.msg = {{0x155, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, // ESP_B (50Hz) + {.msg = {{0x20a, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, // BrakeMessage (50Hz) + {.msg = {{0x368, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // DI_state (10Hz) + {.msg = {{0x318, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // GTW_carState (10Hz) +}; +#define TESLA_RX_CHECK_LEN (sizeof(tesla_rx_checks) / sizeof(tesla_rx_checks[0])) +bool autopilot_enabled = false; static int tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { - set_gmlan_digital_output(0); // #define GMLAN_HIGH 0 - reset_gmlan_switch_timeout(); //we're still in tesla safety mode, reset the timeout counter and make sure our output is enabled + bool valid = addr_safety_check(to_push, tesla_rx_checks, TESLA_RX_CHECK_LEN, + NULL, NULL, NULL); - int addr = GET_ADDR(to_push); + if(valid) { + int bus = GET_BUS(to_push); + int addr = GET_ADDR(to_push); - if (addr == 0x45) { - // 6 bits starting at position 0 - int lever_position = GET_BYTE(to_push, 0) & 0x3F; - if (lever_position == 2) { // pull forward - // activate openpilot - controls_allowed = 1; + if(bus == 0) { + if(addr == 0x370) { + // Steering angle: (0.1 * val) - 819.2 in deg. + // Store it 1/10 deg to match steering request + int angle_meas_new = (((GET_BYTE(to_push, 4) & 0x3F) << 8) | GET_BYTE(to_push, 5)) - 8192; + update_sample(&angle_meas, angle_meas_new); + } + + if(addr == 0x155) { + // Vehicle speed: (0.01 * val) * KPH_TO_MPS + vehicle_speed = ((GET_BYTE(to_push, 5) << 8) | (GET_BYTE(to_push, 6))) * 0.01 / 3.6; + vehicle_moving = vehicle_speed > 0.; + } + + if(addr == 0x108) { + // Gas pressed + gas_pressed = (GET_BYTE(to_push, 6) != 0); + } + + if(addr == 0x20a) { + // Brake pressed + brake_pressed = (((GET_BYTE(to_push, 0) & 0x0C) >> 2) != 1); + } + + if(addr == 0x368) { + // Cruise state + int cruise_state = (GET_BYTE(to_push, 1) >> 4); + bool cruise_engaged = (cruise_state == 2) || // ENABLED + (cruise_state == 3) || // STANDSTILL + (cruise_state == 4) || // OVERRIDE + (cruise_state == 6) || // PRE_FAULT + (cruise_state == 7); // PRE_CANCEL + + if(cruise_engaged && !cruise_engaged_prev) { + controls_allowed = 1; + } + if(!cruise_engaged) { + controls_allowed = 0; + } + cruise_engaged_prev = cruise_engaged; + } } - if (lever_position == 1) { // push towards the back - // deactivate openpilot - controls_allowed = 0; + + if (bus == 2) { + if (addr == 0x399) { + // Autopilot status + int autopilot_status = (GET_BYTE(to_push, 0) & 0xF); + autopilot_enabled = (autopilot_status == 3) || // ACTIVE_1 + (autopilot_status == 4) || // ACTIVE_2 + (autopilot_status == 5); // ACTIVE_NAVIGATE_ON_AUTOPILOT + + if (autopilot_enabled) { + controls_allowed = 0; + } + } } + + // 0x488: DAS_steeringControl should not be received on bus 0 + generic_rx_checks((addr == 0x488) && (bus == 0)); } - // exit controls on brake press - // DI_torque2::DI_brakePedal 0x118 - if (addr == 0x118) { - // 1 bit at position 16 - if ((GET_BYTE(to_push, 1) & 0x80) != 0) { - // disable break cancel by commenting line below - controls_allowed = 0; - } - //get vehicle speed in m/s. Tesla gives MPH - tesla_speed = (((((GET_BYTE(to_push, 3) & 0xF) << 8) + GET_BYTE(to_push, 2)) * 0.05) - 25) * 1.609 / 3.6; - if (tesla_speed < 0) { - tesla_speed = 0; - } - } - - // exit controls on EPAS error - // EPAS_sysStatus::EPAS_eacStatus 0x370 - if (addr == 0x370) { - // if EPAS_eacStatus is not 1 or 2, disable control - eac_status = (GET_BYTE(to_push, 6) >> 5) & 0x7; - // For human steering override we must not disable controls when eac_status == 0 - // Additional safety: we could only allow eac_status == 0 when we have human steering allowed - if (controls_allowed && (eac_status != 0) && (eac_status != 1) && (eac_status != 2)) { - controls_allowed = 0; - //puts("EPAS error! \n"); - } - } - //get latest steering wheel angle - if (addr == 0x00E) { - float angle_meas_now = (int)(((((GET_BYTE(to_push, 0) & 0x3F) << 8) + GET_BYTE(to_push, 1)) * 0.1) - 819.2); - uint32_t ts = TIM2->CNT; - uint32_t ts_elapsed = get_ts_elapsed(ts, tesla_ts_angle_last); - - // *** angle real time check - // add 1 to not false trigger the violation and multiply by 25 since the check is done every 250 ms and steer angle is updated at 100Hz - float rt_delta_angle_up = (interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) * 25.) + 1.; - float rt_delta_angle_down = (interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) * 25.) + 1.; - float highest_rt_angle = tesla_rt_angle_last + ((tesla_rt_angle_last > 0.) ? rt_delta_angle_up : rt_delta_angle_down); - float lowest_rt_angle = tesla_rt_angle_last - ((tesla_rt_angle_last > 0.) ? rt_delta_angle_down : rt_delta_angle_up); - - if ((ts_elapsed > TESLA_RT_INTERVAL) || (controls_allowed && !tesla_controls_allowed_last)) { - tesla_rt_angle_last = angle_meas_now; - tesla_ts_angle_last = ts; - } - - // check for violation; - if (fmax_limit_check(angle_meas_now, highest_rt_angle, lowest_rt_angle)) { - // We should not be able to STEER under these conditions - // Other sending is fine (to allow human override) - controls_allowed = 0; - //puts("WARN: RT Angle - No steer allowed! \n"); - } else { - controls_allowed = 1; - } - - tesla_controls_allowed_last = controls_allowed; - } - return 1; + return valid; } -// all commands: gas/regen, friction brake and steering -// if controls_allowed and no pedals pressed -// allow all commands up to limit -// else -// block all commands that produce actuation static int tesla_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { - int tx = 1; int addr = GET_ADDR(to_send); + bool violation = false; - // do not transmit CAN message if steering angle too high - // DAS_steeringControl::DAS_steeringAngleRequest - if (addr == 0x488) { - float angle_raw = ((GET_BYTE(to_send, 0) & 0x7F) << 8) + GET_BYTE(to_send, 1); - float desired_angle = (angle_raw * 0.1) - 1638.35; - bool violation = 0; - int st_enabled = GET_BYTE(to_send, 2) & 0x40; + if(!msg_allowed(to_send, TESLA_TX_MSGS, sizeof(TESLA_TX_MSGS) / sizeof(TESLA_TX_MSGS[0]))) { + tx = 0; + } - if (st_enabled == 0) { - //steering is not enabled, do not check angles and do send - tesla_desired_angle_last = desired_angle; - } else if (controls_allowed) { - // add 1 to not false trigger the violation - float delta_angle_up = interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) + 1.; - float delta_angle_down = interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) + 1.; - float highest_desired_angle = tesla_desired_angle_last + ((tesla_desired_angle_last > 0.) ? delta_angle_up : delta_angle_down); - float lowest_desired_angle = tesla_desired_angle_last - ((tesla_desired_angle_last > 0.) ? delta_angle_down : delta_angle_up); - float TESLA_MAX_ANGLE = interpolate(TESLA_LOOKUP_MAX_ANGLE, tesla_speed) + 1.; + if(relay_malfunction) { + tx = 0; + } - //check for max angles - violation |= fmax_limit_check(desired_angle, TESLA_MAX_ANGLE, -TESLA_MAX_ANGLE); + if(addr == 0x488) { + // Steering control: (0.1 * val) - 1638.35 in deg. + // We use 1/10 deg as a unit here + int raw_angle_can = (((GET_BYTE(to_send, 0) & 0x7F) << 8) | GET_BYTE(to_send, 1)); + int desired_angle = raw_angle_can - 16384; + int steer_control_type = GET_BYTE(to_send, 2) >> 6; + bool steer_control_enabled = (steer_control_type != 0) && // NONE + (steer_control_type != 3); // DISABLED - //check for angle delta changes - violation |= fmax_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + // Rate limit while steering + if(controls_allowed && steer_control_enabled) { + // Add 1 to not false trigger the violation + float delta_angle_float; + delta_angle_float = (interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, vehicle_speed) * TESLA_DEG_TO_CAN); + int delta_angle_up = (int)(delta_angle_float) + 1; + delta_angle_float = (interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, vehicle_speed) * TESLA_DEG_TO_CAN); + int delta_angle_down = (int)(delta_angle_float) + 1; + int highest_desired_angle = desired_angle_last + ((desired_angle_last > 0) ? delta_angle_up : delta_angle_down); + int lowest_desired_angle = desired_angle_last - ((desired_angle_last >= 0) ? delta_angle_down : delta_angle_up); - if (violation) { - controls_allowed = 0; - tx = 0; - } - tesla_desired_angle_last = desired_angle; - } else { - tx = 0; + // Check for violation; + violation |= max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + } + desired_angle_last = desired_angle; + + // Angle should be the same as current angle while not steering + if(!controls_allowed && ((desired_angle < (angle_meas.min - 1)) || (desired_angle > (angle_meas.max + 1)))) { + violation = true; + } + + // No angle control allowed when controls are not allowed + if(!controls_allowed && steer_control_enabled) { + violation = true; } } + + if(addr == 0x45) { + // No button other than cancel can be sent by us + int control_lever_status = (GET_BYTE(to_send, 0) & 0x3F); + if((control_lever_status != 0) && (control_lever_status != 1)) { + violation = true; + } + } + + if(violation) { + controls_allowed = 0; + tx = 0; + } + return tx; } +static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + int bus_fwd = -1; + int addr = GET_ADDR(to_fwd); + + if(bus_num == 0) { + // Chassis to autopilot + bus_fwd = 2; + } + + if(bus_num == 2) { + // Autopilot to chassis + bool block_msg = ((addr == 0x488) && !autopilot_enabled); + if(!block_msg) { + bus_fwd = 0; + } + } + + if(relay_malfunction) { + bus_fwd = -1; + } + + return bus_fwd; +} + static void tesla_init(int16_t param) { UNUSED(param); controls_allowed = 0; - gmlan_switch_init(1); //init the gmlan switch with 1s timeout enabled -} - -static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { - - int bus_fwd = -1; - int addr = GET_ADDR(to_fwd); - - if (bus_num == 0) { - // change inhibit of GTW_epasControl - - if (addr != 0x214) { - // remove EPB_epasControl - bus_fwd = 2; // Custom EPAS bus - } - if (addr == 0x101) { - to_fwd->RDLR = GET_BYTES_04(to_fwd) | 0x4000; // 0x4000: WITH_ANGLE, 0xC000: WITH_BOTH (angle and torque) - uint32_t checksum = (GET_BYTE(to_fwd, 1) + GET_BYTE(to_fwd, 0) + 2) & 0xFF; - to_fwd->RDLR = GET_BYTES_04(to_fwd) & 0xFFFF; - to_fwd->RDLR = GET_BYTES_04(to_fwd) + (checksum << 16); - } - } - if (bus_num == 2) { - // remove GTW_epasControl in forwards - if (addr != 0x101) { - bus_fwd = 0; // Chassis CAN - } - } - return bus_fwd; + relay_malfunction_reset(); } const safety_hooks tesla_hooks = { @@ -209,4 +201,6 @@ const safety_hooks tesla_hooks = { .tx = tesla_tx_hook, .tx_lin = nooutput_tx_lin_hook, .fwd = tesla_fwd_hook, + .addr_check = tesla_rx_checks, + .addr_check_len = TESLA_RX_CHECK_LEN, }; diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h index 241e5798f..794d0d54d 100644 --- a/panda/board/safety/safety_toyota.h +++ b/panda/board/safety/safety_toyota.h @@ -35,11 +35,11 @@ const CanMsg TOYOTA_TX_MSGS[] = {{0x283, 0, 7}, {0x2E6, 0, 8}, {0x2E7, 0, 8}, {0 {0x200, 0, 6}}; // interceptor AddrCheckStruct toyota_rx_checks[] = { - {.msg = {{ 0xaa, 0, 8, .check_checksum = false, .expected_timestep = 12000U}}}, - {.msg = {{0x260, 0, 8, .check_checksum = true, .expected_timestep = 20000U}}}, - {.msg = {{0x1D2, 0, 8, .check_checksum = true, .expected_timestep = 30000U}}}, + {.msg = {{ 0xaa, 0, 8, .check_checksum = false, .expected_timestep = 12000U}, { 0 }, { 0 }}}, + {.msg = {{0x260, 0, 8, .check_checksum = true, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{0x1D2, 0, 8, .check_checksum = true, .expected_timestep = 30000U}, { 0 }, { 0 }}}, {.msg = {{0x224, 0, 8, .check_checksum = false, .expected_timestep = 25000U}, - {0x226, 0, 8, .check_checksum = false, .expected_timestep = 25000U}}}, + {0x226, 0, 8, .check_checksum = false, .expected_timestep = 25000U}, { 0 }}}, }; const int TOYOTA_RX_CHECKS_LEN = sizeof(toyota_rx_checks) / sizeof(toyota_rx_checks[0]); @@ -201,7 +201,7 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { desired_torque = to_signed(desired_torque, 16); bool violation = 0; - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); if (controls_allowed) { diff --git a/panda/board/safety/safety_volkswagen.h b/panda/board/safety/safety_volkswagen.h index 3df1fcbd0..77b58310f 100644 --- a/panda/board/safety/safety_volkswagen.h +++ b/panda/board/safety/safety_volkswagen.h @@ -22,11 +22,11 @@ const CanMsg VOLKSWAGEN_MQB_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, const int VOLKSWAGEN_MQB_TX_MSGS_LEN = sizeof(VOLKSWAGEN_MQB_TX_MSGS) / sizeof(VOLKSWAGEN_MQB_TX_MSGS[0]); AddrCheckStruct volkswagen_mqb_rx_checks[] = { - {.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}}}, - {.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}}}, - {.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, + {.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, }; const int VOLKSWAGEN_MQB_RX_CHECKS_LEN = sizeof(volkswagen_mqb_rx_checks) / sizeof(volkswagen_mqb_rx_checks[0]); @@ -44,10 +44,10 @@ const CanMsg VOLKSWAGEN_PQ_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_GRA_NEU, 0, 4}, const int VOLKSWAGEN_PQ_TX_MSGS_LEN = sizeof(VOLKSWAGEN_PQ_TX_MSGS) / sizeof(VOLKSWAGEN_PQ_TX_MSGS[0]); AddrCheckStruct volkswagen_pq_rx_checks[] = { - {.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}}}, - {.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 20000U}}}, - {.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}}}, - {.msg = {{MSG_BREMSE_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}}}, + {.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_BREMSE_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, }; const int VOLKSWAGEN_PQ_RX_CHECKS_LEN = sizeof(volkswagen_pq_rx_checks) / sizeof(volkswagen_pq_rx_checks[0]); @@ -244,7 +244,7 @@ static int volkswagen_pq_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { static bool volkswagen_steering_check(int desired_torque) { bool violation = false; - uint32_t ts = TIM2->CNT; + uint32_t ts = microsecond_timer_get(); if (controls_allowed) { // *** global torque limit check *** diff --git a/panda/board/safety_declarations.h b/panda/board/safety_declarations.h index 3f8221c97..126f42d8a 100644 --- a/panda/board/safety_declarations.h +++ b/panda/board/safety_declarations.h @@ -6,7 +6,7 @@ struct sample_t { int values[6]; int min; int max; -} sample_t_default = {{0}, 0, 0}; +} sample_t_default = {.values = {0}, .min = 0, .max = 0}; // safety code requires floats struct lookup_t { diff --git a/panda/board/spi_flasher.h b/panda/board/spi_flasher.h index 2636bf535..cbc1c428c 100644 --- a/panda/board/spi_flasher.h +++ b/panda/board/spi_flasher.h @@ -153,7 +153,7 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { #ifdef PEDAL -#include "drivers/llcan.h" +#include "stm32fx/llcan.h" #define CAN CAN1 #define CAN_BL_INPUT 0x1 @@ -313,7 +313,7 @@ void soft_flasher_start(void) { GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; // flasher - spi_init(); + //spi_init(); // enable USB usb_init(); @@ -340,4 +340,3 @@ void soft_flasher_start(void) { delay(500000); } } - diff --git a/panda/board/board.h b/panda/board/stm32fx/board.h similarity index 66% rename from panda/board/board.h rename to panda/board/stm32fx/board.h index 19392c9ea..4cf350536 100644 --- a/panda/board/board.h +++ b/panda/board/stm32fx/board.h @@ -1,15 +1,16 @@ // ///////////////////////////////////////////////////////////// // // Hardware abstraction layer for all different supported boards // // ///////////////////////////////////////////////////////////// // -#include "board_declarations.h" -#include "boards/common.h" +#include "boards/board_declarations.h" // ///// Board definition and detection ///// // #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 "stm32fx/clock_source.h" #include "boards/white.h" #include "boards/grey.h" #include "boards/black.h" @@ -51,37 +52,9 @@ void detect_board_type(void) { #endif } - -// ///// Configuration detection ///// // bool has_external_debug_serial = 0; -void detect_configuration(void) { +void detect_external_debug_serial(void) { // detect if external serial debugging is present has_external_debug_serial = detect_with_pull(GPIOA, 3, PULL_DOWN); } - -// ///// Board functions ///// // -// TODO: Make these config options in the board struct -bool board_has_gps(void) { - return ((hw_type == HW_TYPE_GREY_PANDA) || (hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO)); -} - -bool board_has_gmlan(void) { - return ((hw_type == HW_TYPE_WHITE_PANDA) || (hw_type == HW_TYPE_GREY_PANDA)); -} - -bool board_has_obd(void) { - return ((hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO) || (hw_type == HW_TYPE_DOS)); -} - -bool board_has_lin(void) { - return ((hw_type == HW_TYPE_WHITE_PANDA) || (hw_type == HW_TYPE_GREY_PANDA)); -} - -bool board_has_rtc(void) { - return ((hw_type == HW_TYPE_UNO) || (hw_type == HW_TYPE_DOS)); -} - -bool board_has_relay(void) { - return ((hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO) || (hw_type == HW_TYPE_DOS)); -} diff --git a/panda/board/drivers/clock.h b/panda/board/stm32fx/clock.h similarity index 99% rename from panda/board/drivers/clock.h rename to panda/board/stm32fx/clock.h index b75692438..4f7beaae4 100644 --- a/panda/board/drivers/clock.h +++ b/panda/board/stm32fx/clock.h @@ -37,4 +37,3 @@ void watchdog_init(void) { void watchdog_feed(void) { IWDG->KR = 0xAAAAU; } - diff --git a/panda/board/drivers/clock_source.h b/panda/board/stm32fx/clock_source.h similarity index 95% rename from panda/board/drivers/clock_source.h rename to panda/board/stm32fx/clock_source.h index 966dee452..691010bd3 100644 --- a/panda/board/drivers/clock_source.h +++ b/panda/board/stm32fx/clock_source.h @@ -24,6 +24,7 @@ void TIM1_UP_TIM10_IRQ_Handler(void) { // Start clock pulse set_gpio_output(GPIOB, 14, true); set_gpio_output(GPIOB, 15, true); + set_gpio_output(GPIOC, 5, true); } // Reset interrupt @@ -37,6 +38,7 @@ void TIM1_CC_IRQ_Handler(void) { // End clock pulse set_gpio_output(GPIOB, 14, false); set_gpio_output(GPIOB, 15, false); + set_gpio_output(GPIOC, 5, false); } // Reset interrupt @@ -55,7 +57,7 @@ void clock_source_init(uint8_t mode){ // Setup timer REGISTER_INTERRUPT(TIM1_UP_TIM10_IRQn, TIM1_UP_TIM10_IRQ_Handler, (1200U / CLOCK_SOURCE_PERIOD_MS) , FAULT_INTERRUPT_RATE_TIM1) REGISTER_INTERRUPT(TIM1_CC_IRQn, TIM1_CC_IRQ_Handler, (1200U / CLOCK_SOURCE_PERIOD_MS) , FAULT_INTERRUPT_RATE_TIM1) - register_set(&(TIM1->PSC), (9600-1), 0xFFFFU); // Tick on 0.1 ms + register_set(&(TIM1->PSC), ((APB2_FREQ*100U)-1U), 0xFFFFU); // Tick on 0.1 ms register_set(&(TIM1->ARR), ((CLOCK_SOURCE_PERIOD_MS*10U) - 1U), 0xFFFFU); // Period register_set(&(TIM1->CCMR1), 0U, 0xFFFFU); // No output on compare register_set_bits(&(TIM1->CCER), TIM_CCER_CC1E); // Enable compare 1 @@ -97,4 +99,4 @@ void clock_source_init(uint8_t mode){ puts("Unknown clock source mode: "); puth(mode); puts("\n"); break; } -} \ No newline at end of file +} diff --git a/panda/board/inc/cmsis_compiler.h b/panda/board/stm32fx/inc/cmsis_compiler.h similarity index 100% rename from panda/board/inc/cmsis_compiler.h rename to panda/board/stm32fx/inc/cmsis_compiler.h diff --git a/panda/board/inc/cmsis_gcc.h b/panda/board/stm32fx/inc/cmsis_gcc.h similarity index 100% rename from panda/board/inc/cmsis_gcc.h rename to panda/board/stm32fx/inc/cmsis_gcc.h diff --git a/panda/board/inc/cmsis_version.h b/panda/board/stm32fx/inc/cmsis_version.h similarity index 100% rename from panda/board/inc/cmsis_version.h rename to panda/board/stm32fx/inc/cmsis_version.h diff --git a/panda/board/inc/core_cm3.h b/panda/board/stm32fx/inc/core_cm3.h similarity index 100% rename from panda/board/inc/core_cm3.h rename to panda/board/stm32fx/inc/core_cm3.h diff --git a/panda/board/inc/core_cm4.h b/panda/board/stm32fx/inc/core_cm4.h similarity index 100% rename from panda/board/inc/core_cm4.h rename to panda/board/stm32fx/inc/core_cm4.h diff --git a/panda/board/inc/mpu_armv7.h b/panda/board/stm32fx/inc/mpu_armv7.h similarity index 100% rename from panda/board/inc/mpu_armv7.h rename to panda/board/stm32fx/inc/mpu_armv7.h diff --git a/panda/board/inc/stm32f205xx.h b/panda/board/stm32fx/inc/stm32f205xx.h similarity index 100% rename from panda/board/inc/stm32f205xx.h rename to panda/board/stm32fx/inc/stm32f205xx.h diff --git a/panda/board/inc/stm32f2xx.h b/panda/board/stm32fx/inc/stm32f2xx.h similarity index 100% rename from panda/board/inc/stm32f2xx.h rename to panda/board/stm32fx/inc/stm32f2xx.h diff --git a/panda/board/inc/stm32f2xx_hal_def.h b/panda/board/stm32fx/inc/stm32f2xx_hal_def.h similarity index 100% rename from panda/board/inc/stm32f2xx_hal_def.h rename to panda/board/stm32fx/inc/stm32f2xx_hal_def.h diff --git a/panda/board/inc/stm32f2xx_hal_gpio_ex.h b/panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h similarity index 100% rename from panda/board/inc/stm32f2xx_hal_gpio_ex.h rename to panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h diff --git a/panda/board/inc/stm32f413xx.h b/panda/board/stm32fx/inc/stm32f413xx.h similarity index 100% rename from panda/board/inc/stm32f413xx.h rename to panda/board/stm32fx/inc/stm32f413xx.h diff --git a/panda/board/inc/stm32f4xx.h b/panda/board/stm32fx/inc/stm32f4xx.h similarity index 100% rename from panda/board/inc/stm32f4xx.h rename to panda/board/stm32fx/inc/stm32f4xx.h diff --git a/panda/board/inc/stm32f4xx_hal_def.h b/panda/board/stm32fx/inc/stm32f4xx_hal_def.h similarity index 100% rename from panda/board/inc/stm32f4xx_hal_def.h rename to panda/board/stm32fx/inc/stm32f4xx_hal_def.h diff --git a/panda/board/inc/stm32f4xx_hal_gpio_ex.h b/panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h similarity index 100% rename from panda/board/inc/stm32f4xx_hal_gpio_ex.h rename to panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h diff --git a/panda/board/inc/system_stm32f2xx.h b/panda/board/stm32fx/inc/system_stm32f2xx.h similarity index 100% rename from panda/board/inc/system_stm32f2xx.h rename to panda/board/stm32fx/inc/system_stm32f2xx.h diff --git a/panda/board/inc/system_stm32f4xx.h b/panda/board/stm32fx/inc/system_stm32f4xx.h similarity index 100% rename from panda/board/inc/system_stm32f4xx.h rename to panda/board/stm32fx/inc/system_stm32f4xx.h diff --git a/panda/board/stm32fx/interrupt_handlers.h b/panda/board/stm32fx/interrupt_handlers.h new file mode 100644 index 000000000..3b40f4ee5 --- /dev/null +++ b/panda/board/stm32fx/interrupt_handlers.h @@ -0,0 +1,100 @@ +// ********************* 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/drivers/adc.h b/panda/board/stm32fx/lladc.h similarity index 93% rename from panda/board/drivers/adc.h rename to panda/board/stm32fx/lladc.h index 358497adb..2ae14a2dc 100644 --- a/panda/board/drivers/adc.h +++ b/panda/board/stm32fx/lladc.h @@ -8,6 +8,8 @@ #define ADCCHAN_VOLTAGE 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); diff --git a/panda/board/drivers/llcan.h b/panda/board/stm32fx/llcan.h similarity index 98% rename from panda/board/drivers/llcan.h rename to panda/board/stm32fx/llcan.h index 68ca242bd..78c4c52ca 100644 --- a/panda/board/drivers/llcan.h +++ b/panda/board/stm32fx/llcan.h @@ -14,7 +14,7 @@ #define GET_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) #define GET_BYTES_04(msg) ((msg)->RDLR) #define GET_BYTES_48(msg) ((msg)->RDHR) -#define GET_FLAG(value, mask) (((__typeof__(mask))param & mask) == mask) +#define GET_FLAG(value, mask) (((__typeof__(mask))(value) & (mask)) == (mask)) #define CAN_INIT_TIMEOUT_MS 500U #define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==CAN1) ? "CAN1" : (((CAN_DEV) == CAN2) ? "CAN2" : "CAN3")) @@ -135,4 +135,3 @@ void llcan_clear_send(CAN_TypeDef *CAN_obj) { // cppcheck-suppress selfAssignment ; needed to clear the register CAN_obj->MSR = CAN_obj->MSR; } - diff --git a/panda/board/drivers/dac.h b/panda/board/stm32fx/lldac.h similarity index 90% rename from panda/board/drivers/dac.h rename to panda/board/stm32fx/lldac.h index 4bdb16100..7b2e112be 100644 --- a/panda/board/drivers/dac.h +++ b/panda/board/stm32fx/lldac.h @@ -1,6 +1,3 @@ -void puth(unsigned int i); -void puts(const char *a); - void dac_init(void) { // No buffers required since we have an opamp register_set(&(DAC->DHR12R1), 0U, 0xFFFU); @@ -17,4 +14,3 @@ void dac_set(int channel, uint32_t value) { puts("Failed to set DAC: invalid channel value: 0x"); puth(value); puts("\n"); } } - diff --git a/panda/board/stm32fx/llfan.h b/panda/board/stm32fx/llfan.h new file mode 100644 index 000000000..a9d21f19b --- /dev/null +++ b/panda/board/stm32fx/llfan.h @@ -0,0 +1,23 @@ +// TACH interrupt handler +void EXTI2_IRQ_Handler(void) { + volatile unsigned int pr = EXTI->PR & (1U << 2); + if ((pr & (1U << 2)) != 0U) { + fan_tach_counter++; + } + EXTI->PR = (1U << 2); +} + +void fan_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/llrtc.h b/panda/board/stm32fx/llrtc.h new file mode 100644 index 000000000..1dc137369 --- /dev/null +++ b/panda/board/stm32fx/llrtc.h @@ -0,0 +1,9 @@ +#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) + +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); +} diff --git a/panda/board/drivers/spi.h b/panda/board/stm32fx/llspi.h similarity index 99% rename from panda/board/drivers/spi.h rename to panda/board/stm32fx/llspi.h index 29963b6bd..d07bce352 100644 --- a/panda/board/drivers/spi.h +++ b/panda/board/stm32fx/llspi.h @@ -128,4 +128,4 @@ void spi_init(void) { register_set_bits(&(EXTI->IMR), (1U << 4)); register_set_bits(&(EXTI->FTSR), (1U << 4)); NVIC_EnableIRQ(EXTI4_IRQn); -} \ No newline at end of file +} diff --git a/panda/board/stm32fx/lluart.h b/panda/board/stm32fx/lluart.h new file mode 100644 index 000000000..0fe4ac2d6 --- /dev/null +++ b/panda/board/stm32fx/lluart.h @@ -0,0 +1,230 @@ +// ***************************** 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){ + // Do not read out directly if DMA enabled + if (q->dma_rx == false) { + 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; + // 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(); + } +} + +// This function should be called on: +// * Half-transfer DMA interrupt +// * Full-transfer DMA interrupt +// * UART IDLE detection +uint32_t prev_w_index = 0; +void dma_pointer_handler(uart_ring *q, uint32_t dma_ndtr) { + ENTER_CRITICAL(); + uint32_t w_index = (q->rx_fifo_size - dma_ndtr); + + // Check for new data + if (w_index != prev_w_index){ + // Check for overflow + if ( + ((prev_w_index < q->r_ptr_rx) && (q->r_ptr_rx <= w_index)) || // No rollover + ((w_index < prev_w_index) && ((q->r_ptr_rx <= w_index) || (prev_w_index < q->r_ptr_rx))) // Rollover + ){ + // We lost data. Set the new read pointer to the oldest byte still available + q->r_ptr_rx = (w_index + 1U) % q->rx_fifo_size; + } + + // Set write pointer + q->w_ptr_rx = w_index; + } + + prev_w_index = w_index; + EXIT_CRITICAL(); +} + +// 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 + puts("Encountered UART error: "); puth(err); puts("\n"); + #endif + UART_READ_DR(q->uart) + } + // Send if necessary + uart_tx_ring(q); + + // Run DMA pointer handler if the line is idle + if(q->dma_rx && (status & USART_SR_IDLE)){ + // Reset IDLE flag + UART_READ_DR(q->uart) + + if(q == &uart_ring_gps){ + dma_pointer_handler(&uart_ring_gps, DMA2_Stream5->NDTR); + } else { + #ifdef DEBUG_UART + puts("No IDLE dma_pointer_handler implemented for this UART."); + #endif + } + } + + EXIT_CRITICAL(); +} + +void USART1_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_gps); } +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); } + +void DMA2_Stream5_IRQ_Handler(void) { + ENTER_CRITICAL(); + + // Handle errors + if((DMA2->HISR & DMA_HISR_TEIF5) || (DMA2->HISR & DMA_HISR_DMEIF5) || (DMA2->HISR & DMA_HISR_FEIF5)){ + #ifdef DEBUG_UART + puts("Encountered UART DMA error. Clearing and restarting DMA...\n"); + #endif + + // Clear flags + DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; + + // Re-enable the DMA if necessary + DMA2_Stream5->CR |= DMA_SxCR_EN; + } + + // Re-calculate write pointer and reset flags + dma_pointer_handler(&uart_ring_gps, DMA2_Stream5->NDTR); + DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; + + EXIT_CRITICAL(); +} + +// ***************************** Hardware setup ***************************** + +void dma_rx_init(uart_ring *q) { + // Initialization is UART-dependent + if(q == &uart_ring_gps){ + // DMA2, stream 5, channel 4 + + // Disable FIFO mode (enable direct) + DMA2_Stream5->FCR &= ~DMA_SxFCR_DMDIS; + + // Setup addresses + DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); // Source + DMA2_Stream5->M0AR = (uint32_t)q->elems_rx; // Destination + DMA2_Stream5->NDTR = q->rx_fifo_size; // Number of bytes to copy + + // Circular, Increment memory, byte size, periph -> memory, enable + // Transfer complete, half transfer, transfer error and direct mode error interrupt enable + DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_TEIE | DMA_SxCR_DMEIE | DMA_SxCR_EN; + + // Enable DMA receiver in UART + q->uart->CR3 |= USART_CR3_DMAR; + + // Enable UART IDLE interrupt + q->uart->CR1 |= USART_CR1_IDLEIE; + + // Enable interrupt + NVIC_EnableIRQ(DMA2_Stream5_IRQn); + } else { + puts("Tried to initialize RX DMA for an unsupported UART\n"); + } +} + +#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) { + if (u == USART1) { + // USART1 is on APB2 + u->BRR = __USART_BRR(48000000U, baud); + } else { + u->BRR = __USART_BRR(24000000U, baud); + } +} + +void uart_init(uart_ring *q, int baud) { + // Register interrupts (max data rate: 115200 baud) + if(q->uart == USART1){ + REGISTER_INTERRUPT(USART1_IRQn, USART1_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_1) + } else 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 + } + if(q->dma_rx){ + REGISTER_INTERRUPT(DMA2_Stream5_IRQn, DMA2_Stream5_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_UART_DMA) // Called twice per buffer + } + + // 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 == USART1){ + NVIC_EnableIRQ(USART1_IRQn); + } else 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 + } + + // Initialise RX DMA if used + if(q->dma_rx){ + dma_rx_init(q); + } +} diff --git a/panda/board/stm32fx/llusb.h b/panda/board/stm32fx/llusb.h new file mode 100644 index 000000000..df4747312 --- /dev/null +++ b/panda/board/stm32fx/llusb.h @@ -0,0 +1,102 @@ +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); + puts(" resetting PHY\n");*/ + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); + //puts("AHB idle\n"); + + // reset PHY here + USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); + //puts("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/boards/common.h b/panda/board/stm32fx/peripherals.h similarity index 83% rename from panda/board/boards/common.h rename to panda/board/stm32fx/peripherals.h index d09d5a48f..9522ad3d7 100644 --- a/panda/board/boards/common.h +++ b/panda/board/stm32fx/peripherals.h @@ -1,9 +1,3 @@ -#ifdef STM32F4 - #include "stm32f4xx_hal_gpio_ex.h" -#else - #include "stm32f2xx_hal_gpio_ex.h" -#endif - // Common GPIO initialization void common_init_gpio(void){ // TODO: Is this block actually doing something??? @@ -73,13 +67,6 @@ void peripherals_init(void){ RCC->APB2ENR |= RCC_APB2ENR_TIM9EN; // slow loop } -// Detection with internal pullup -#define PULL_EFFECTIVE_DELAY 4096 -bool detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { - set_gpio_mode(GPIO, pin, MODE_INPUT); - set_gpio_pullup(GPIO, pin, mode); - for (volatile int i=0; iAPB1ENR), RCC_APB1ENR_TIM6EN); // Enable interrupt timer peripheral } diff --git a/panda/board/startup_stm32f205xx.s b/panda/board/stm32fx/startup_stm32f205xx.s similarity index 100% rename from panda/board/startup_stm32f205xx.s rename to panda/board/stm32fx/startup_stm32f205xx.s diff --git a/panda/board/startup_stm32f413xx.s b/panda/board/stm32fx/startup_stm32f413xx.s similarity index 100% rename from panda/board/startup_stm32f413xx.s rename to panda/board/stm32fx/startup_stm32f413xx.s diff --git a/panda/board/stm32fx/stm32fx_config.h b/panda/board/stm32fx/stm32fx_config.h new file mode 100644 index 000000000..8bcbfa320 --- /dev/null +++ b/panda/board/stm32fx/stm32fx_config.h @@ -0,0 +1,88 @@ +#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 +//APB1 - 48Mhz, APB2 - 96Mhz +#define APB1_FREQ CORE_FREQ/2U +#define APB2_FREQ CORE_FREQ/1U + +#define BOOTLOADER_ADDRESS 0x1FFF0004U + +// Around (1Mbps / 8 bits/byte / 12 bytes per message) +#define CAN_INTERRUPT_RATE 12000U + +#define MAX_LED_FADE 8192U + +// Threshold voltage (mV) for either of the SBUs to be below before deciding harness is connected +#define HARNESS_CONNECTED_THRESHOLD 2500U + +#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 PROVISION_CHUNK_ADDRESS 0x1FFF79E0U +#define DEVICE_SERIAL_NUMBER_ADDRESS 0x1FFF79C0U + +#ifndef BOOTSTUB + #ifdef PANDA + #include "main_declarations.h" + #else + #include "pedal/main_declarations.h" + #endif +#else + #include "bootstub_declarations.h" +#endif + +#include "libc.h" +#include "critical.h" +#include "faults.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/lladc.h" +#include "stm32fx/board.h" +#include "stm32fx/clock.h" + +#if !defined (BOOTSTUB) && (defined(PANDA) || defined(PEDAL_USB)) + #include "drivers/uart.h" + #include "stm32fx/lluart.h" +#endif + +#ifndef BOOTSTUB + #include "stm32fx/llcan.h" +#endif + +#if defined(PANDA) || defined(BOOTSTUB) || defined(PEDAL_USB) + #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/stm32_flash.ld b/panda/board/stm32fx/stm32fx_flash.ld similarity index 97% rename from panda/board/stm32_flash.ld rename to panda/board/stm32fx/stm32fx_flash.ld index 500319377..e6b2ef09d 100644 --- a/panda/board/stm32_flash.ld +++ b/panda/board/stm32fx/stm32fx_flash.ld @@ -1,7 +1,7 @@ /* ***************************************************************************** ** -** File : stm32_flash.ld +** File : stm32f4_flash.ld ** ** Abstract : Linker script for STM32F407VG Device with ** 1024KByte FLASH, 192KByte RAM @@ -15,7 +15,7 @@ ** ** Environment : Atollic TrueSTUDIO(R) ** -** Distribution: The file is distributed as is, without any warranty +** Distribution: The file is distributed "as is," without any warranty ** of any kind. ** ** (c)Copyright Atollic AB. diff --git a/panda/board/tests/test_rsa.c b/panda/board/tests/test_rsa.c index f4a7d6be0..5c784e23a 100644 --- a/panda/board/tests/test_rsa.c +++ b/panda/board/tests/test_rsa.c @@ -32,4 +32,3 @@ int main() { return 0; } - diff --git a/panda/examples/query_fw_versions.py b/panda/examples/query_fw_versions.py new file mode 100755 index 000000000..6795f62c2 --- /dev/null +++ b/panda/examples/query_fw_versions.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python3 +import argparse +from tqdm import tqdm +from panda import Panda +from panda.python.uds import UdsClient, MessageTimeoutError, NegativeResponseError, SESSION_TYPE, DATA_IDENTIFIER_TYPE + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument('--rxoffset', default="0x8") + parser.add_argument('--nonstandard', action='store_true') + parser.add_argument('--debug', action='store_true') + parser.add_argument('--addr') + args = parser.parse_args() + + if args.addr: + addrs = [int(args.addr, base=16)] + else: + addrs = [0x700 + i for i in range(256)] + addrs += [0x18da0000 + (i << 8) + 0xf1 for i in range(256)] + results = {} + + uds_data_ids = {} + for std_id in DATA_IDENTIFIER_TYPE: + uds_data_ids[std_id.value] = std_id.name + if args.nonstandard: + for uds_id in range(0xf100,0xf180): + uds_data_ids[uds_id] = "IDENTIFICATION_OPTION_VEHICLE_MANUFACTURER_SPECIFIC_DATA_IDENTIFIER" + for uds_id in range(0xf1a0,0xf1f0): + uds_data_ids[uds_id] = "IDENTIFICATION_OPTION_VEHICLE_MANUFACTURER_SPECIFIC" + for uds_id in range(0xf1f0,0xf200): + uds_data_ids[uds_id] = "IDENTIFICATION_OPTION_SYSTEM_SUPPLIER_SPECIFIC" + + panda = Panda() + panda.set_safety_mode(Panda.SAFETY_ELM327) + panda.set_power_save(0) + print("querying addresses ...") + with tqdm(addrs) as t: + for addr in t: + # skip functional broadcast addrs + if addr == 0x7df or addr == 0x18db33f1: + continue + t.set_description(hex(addr)) + + uds_client = UdsClient(panda, addr, addr + int(args.rxoffset, base=16), bus=1 if panda.has_obd() else 0, timeout=0.2, debug=args.debug) + # Check for anything alive at this address, and switch to the highest + # available diagnostic session without security access + try: + uds_client.tester_present() + uds_client.diagnostic_session_control(SESSION_TYPE.DEFAULT) + uds_client.diagnostic_session_control(SESSION_TYPE.EXTENDED_DIAGNOSTIC) + except NegativeResponseError: + pass + except MessageTimeoutError: + continue + + # Run queries against all standard UDS data identifiers, plus selected + # non-standardized identifier ranges if requested + resp = {} + for uds_data_id in sorted(uds_data_ids): + try: + data = uds_client.read_data_by_identifier(uds_data_id) # type: ignore + if data: + resp[uds_data_id] = data + except (NegativeResponseError, MessageTimeoutError): + pass + + if resp.keys(): + results[addr] = resp + + if len(results.items()): + for addr, resp in results.items(): + print(f"\n\n*** Results for address 0x{addr:X} ***\n\n") + for rid, dat in resp.items(): + print(f"0x{rid:02X} {uds_data_ids[rid]}: {dat}") + else: + print("no fw versions found!") diff --git a/panda/python/__init__.py b/panda/python/__init__.py index 1ef4d2a4a..a4b0dbba0 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -138,11 +138,15 @@ class Panda(object): HW_TYPE_BLACK_PANDA = b'\x03' HW_TYPE_PEDAL = b'\x04' HW_TYPE_UNO = b'\x05' + HW_TYPE_DOS = b'\x06' CLOCK_SOURCE_MODE_DISABLED = 0 CLOCK_SOURCE_MODE_FREE_RUNNING = 1 CLOCK_SOURCE_MODE_EXTERNAL_SYNC = 2 + FLAG_HONDA_ALT_BRAKE = 1 + FLAG_HONDA_BOSCH_LONG = 2 + def __init__(self, serial=None, claim=True): self._serial = serial self._handle = None @@ -177,7 +181,6 @@ class Panda(object): self._serial = this_serial print("opening device", self._serial, hex(device.getProductID())) self.bootstub = device.getProductID() == 0xddee - self.legacy = (device.getbcdDevice() != 0x2300) self._handle = device.open() if sys.platform not in ["win32", "cygwin", "msys", "darwin"]: self._handle.setAutoDetachKernelDriver(True) @@ -390,11 +393,17 @@ class Panda(object): def is_black(self): return self.get_type() == Panda.HW_TYPE_BLACK_PANDA + def is_pedal(self): + return self.get_type() == Panda.HW_TYPE_PEDAL + def is_uno(self): return self.get_type() == Panda.HW_TYPE_UNO + def is_dos(self): + return self.get_type() == Panda.HW_TYPE_DOS + def has_obd(self): - return (self.is_uno() or self.is_black()) + return (self.is_uno() or self.is_dos() or self.is_black()) def get_serial(self): dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20) @@ -420,8 +429,10 @@ class Panda(object): self._handle.controlWrite(Panda.REQUEST_OUT, 0xda, int(bootmode), 0, b'') time.sleep(0.2) - def set_safety_mode(self, mode=SAFETY_SILENT): + def set_safety_mode(self, mode=SAFETY_SILENT, disable_heartbeat=True): self._handle.controlWrite(Panda.REQUEST_OUT, 0xdc, mode, 0, b'') + if disable_heartbeat: + self.set_heartbeat_disabled() def set_can_forwarding(self, from_bus, to_bus): # TODO: This feature may not work correctly with saturated buses @@ -619,6 +630,11 @@ class Panda(object): def send_heartbeat(self): self._handle.controlWrite(Panda.REQUEST_OUT, 0xf3, 0, 0, b'') + # disable heartbeat checks for use outside of openpilot + # sending a heartbeat will reenable the checks + def set_heartbeat_disabled(self): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf8, 0, 0, b'') + # ******************* RTC ******************* def set_datetime(self, dt): self._handle.controlWrite(Panda.REQUEST_OUT, 0xa1, int(dt.year), 0, b'') diff --git a/panda/python/dfu.py b/panda/python/dfu.py index f0e055878..e7d1d9151 100644 --- a/panda/python/dfu.py +++ b/panda/python/dfu.py @@ -22,7 +22,6 @@ class PandaDFU(object): continue if this_dfu_serial == dfu_serial or dfu_serial is None: self._handle = device.open() - self.legacy = "07*128Kg" in self._handle.getASCIIStringDescriptor(4) return raise Exception("failed to open " + dfu_serial if dfu_serial is not None else "DFU device") diff --git a/panda/python/serial.py b/panda/python/serial.py index 93ed2dfe4..97fe8f1d9 100644 --- a/panda/python/serial.py +++ b/panda/python/serial.py @@ -4,6 +4,7 @@ class PandaSerial(object): self.panda = panda self.port = port self.panda.set_uart_parity(self.port, 0) + self._baudrate = baud self.panda.set_uart_baud(self.port, baud) self.buf = b"" @@ -20,3 +21,15 @@ class PandaSerial(object): def close(self): pass + + def flush(self): + pass + + @property + def baudrate(self): + return self._baudrate + + @baudrate.setter + def baudrate(self, value): + self.panda.set_uart_baud(self.port, value) + self._baudrate = value diff --git a/selfdrive/assets/images/network_0.png b/selfdrive/assets/images/network_0.png deleted file mode 100644 index 2ce959ca5..000000000 Binary files a/selfdrive/assets/images/network_0.png and /dev/null differ diff --git a/selfdrive/assets/images/network_1.png b/selfdrive/assets/images/network_1.png deleted file mode 100644 index d7ae713f9..000000000 Binary files a/selfdrive/assets/images/network_1.png and /dev/null differ diff --git a/selfdrive/assets/images/network_2.png b/selfdrive/assets/images/network_2.png deleted file mode 100644 index 17ecd977f..000000000 Binary files a/selfdrive/assets/images/network_2.png and /dev/null differ diff --git a/selfdrive/assets/images/network_3.png b/selfdrive/assets/images/network_3.png deleted file mode 100644 index 1e854e678..000000000 Binary files a/selfdrive/assets/images/network_3.png and /dev/null differ diff --git a/selfdrive/assets/images/network_4.png b/selfdrive/assets/images/network_4.png deleted file mode 100644 index 08c9ab91f..000000000 Binary files a/selfdrive/assets/images/network_4.png and /dev/null differ diff --git a/selfdrive/assets/images/network_5.png b/selfdrive/assets/images/network_5.png deleted file mode 100644 index fba67a95a..000000000 Binary files a/selfdrive/assets/images/network_5.png and /dev/null differ diff --git a/selfdrive/assets/offroad/icon_close.svg b/selfdrive/assets/offroad/icon_close.svg new file mode 100644 index 000000000..4c063371a --- /dev/null +++ b/selfdrive/assets/offroad/icon_close.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/offroad/icon_lock_closed.svg b/selfdrive/assets/offroad/icon_lock_closed.svg new file mode 100644 index 000000000..b78709740 --- /dev/null +++ b/selfdrive/assets/offroad/icon_lock_closed.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/offroad/tc.html b/selfdrive/assets/offroad/tc.html index 35e791f7f..70d08906f 100644 --- a/selfdrive/assets/offroad/tc.html +++ b/selfdrive/assets/offroad/tc.html @@ -4,14 +4,13 @@ openpilot Terms of Service -

openpilot Terms and Conditions

The Terms and Conditions below are effective for all users

Last Updated on October 18, 2019

Please read these Terms of Use (“Terms”) carefully before using openpilot which is open-sourced software developed by Comma.ai, Inc., a corporation organized under the laws of Delaware (“comma,” “us,” “we,” or “our”).

diff --git a/selfdrive/assets/training/step0.png b/selfdrive/assets/training/step0.png index badeff6c5..c5401136e 100644 Binary files a/selfdrive/assets/training/step0.png and b/selfdrive/assets/training/step0.png differ diff --git a/selfdrive/assets/training/step1.png b/selfdrive/assets/training/step1.png index 9fa6cf683..5976ce034 100644 Binary files a/selfdrive/assets/training/step1.png and b/selfdrive/assets/training/step1.png differ diff --git a/selfdrive/assets/training/step10.png b/selfdrive/assets/training/step10.png index 10d216c8f..7c9c78130 100644 Binary files a/selfdrive/assets/training/step10.png and b/selfdrive/assets/training/step10.png differ diff --git a/selfdrive/assets/training/step11.png b/selfdrive/assets/training/step11.png index 71d98864f..cdfd0fad1 100644 Binary files a/selfdrive/assets/training/step11.png and b/selfdrive/assets/training/step11.png differ diff --git a/selfdrive/assets/training/step12.png b/selfdrive/assets/training/step12.png index 627f235ca..1196e0736 100644 Binary files a/selfdrive/assets/training/step12.png and b/selfdrive/assets/training/step12.png differ diff --git a/selfdrive/assets/training/step13.png b/selfdrive/assets/training/step13.png index 2430c6c80..eff7ed2e9 100644 Binary files a/selfdrive/assets/training/step13.png and b/selfdrive/assets/training/step13.png differ diff --git a/selfdrive/assets/training/step14.png b/selfdrive/assets/training/step14.png index 835d6e24f..f1975cc0b 100644 Binary files a/selfdrive/assets/training/step14.png and b/selfdrive/assets/training/step14.png differ diff --git a/selfdrive/assets/training/step15.png b/selfdrive/assets/training/step15.png index c65b0e2af..3479764e2 100644 Binary files a/selfdrive/assets/training/step15.png and b/selfdrive/assets/training/step15.png differ diff --git a/selfdrive/assets/training/step16.png b/selfdrive/assets/training/step16.png index bff559846..a1f2ac263 100644 Binary files a/selfdrive/assets/training/step16.png and b/selfdrive/assets/training/step16.png differ diff --git a/selfdrive/assets/training/step17.png b/selfdrive/assets/training/step17.png index 81d214d0a..b35a17374 100644 Binary files a/selfdrive/assets/training/step17.png and b/selfdrive/assets/training/step17.png differ diff --git a/selfdrive/assets/training/step2.png b/selfdrive/assets/training/step2.png index ab1498bcc..58003315d 100644 Binary files a/selfdrive/assets/training/step2.png and b/selfdrive/assets/training/step2.png differ diff --git a/selfdrive/assets/training/step3.png b/selfdrive/assets/training/step3.png index d19e388ed..e31044b85 100644 Binary files a/selfdrive/assets/training/step3.png and b/selfdrive/assets/training/step3.png differ diff --git a/selfdrive/assets/training/step4.png b/selfdrive/assets/training/step4.png index 874b19390..57e5e234f 100644 Binary files a/selfdrive/assets/training/step4.png and b/selfdrive/assets/training/step4.png differ diff --git a/selfdrive/assets/training/step5.png b/selfdrive/assets/training/step5.png index 9ee3388c3..af9fbd58c 100644 Binary files a/selfdrive/assets/training/step5.png and b/selfdrive/assets/training/step5.png differ diff --git a/selfdrive/assets/training/step6.png b/selfdrive/assets/training/step6.png index 14463ea04..c8ca6b526 100644 Binary files a/selfdrive/assets/training/step6.png and b/selfdrive/assets/training/step6.png differ diff --git a/selfdrive/assets/training/step7.png b/selfdrive/assets/training/step7.png index 682333214..28af33b91 100644 Binary files a/selfdrive/assets/training/step7.png and b/selfdrive/assets/training/step7.png differ diff --git a/selfdrive/assets/training/step8.png b/selfdrive/assets/training/step8.png index 1a5bb1367..615a80922 100644 Binary files a/selfdrive/assets/training/step8.png and b/selfdrive/assets/training/step8.png differ diff --git a/selfdrive/assets/training/step9.png b/selfdrive/assets/training/step9.png index f9b53cf7a..f8ed28da5 100644 Binary files a/selfdrive/assets/training/step9.png and b/selfdrive/assets/training/step9.png differ diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 1659b692c..720fd8926 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -54,7 +54,7 @@ def handle_long_poll(ws): threads = [ threading.Thread(target=ws_recv, args=(ws, end_event), name='ws_recv'), - threading.Thread(target=ws_send, args=(ws, end_event), name='wc_send'), + threading.Thread(target=ws_send, args=(ws, end_event), name='ws_send'), threading.Thread(target=upload_handler, args=(end_event,), name='upload_handler'), threading.Thread(target=log_handler, args=(end_event,), name='log_handler'), ] + [ @@ -116,7 +116,7 @@ def _do_upload(upload_item): return requests.put(upload_item.url, data=f, headers={**upload_item.headers, 'Content-Length': str(size)}, - timeout=10) + timeout=30) # security: user should be able to request any message from their car @@ -267,6 +267,11 @@ def getNetworkType(): return HARDWARE.get_network_type() +@dispatcher.add_method +def getNetworks(): + return HARDWARE.get_networks() + + @dispatcher.add_method def takeSnapshot(): from selfdrive.camerad.snapshot.snapshot import snapshot, jpeg_write @@ -424,7 +429,7 @@ def ws_recv(ws, end_event): except WebSocketTimeoutException: ns_since_last_ping = int(sec_since_boot() * 1e9) - last_ping if ns_since_last_ping > RECONNECT_TIMEOUT_S * 1e9: - cloudlog.exception("athenad.wc_recv.timeout") + cloudlog.exception("athenad.ws_recv.timeout") end_event.set() except Exception: cloudlog.exception("athenad.ws_recv.exception") @@ -479,8 +484,7 @@ def main(): ws = create_connection(ws_uri, cookie="jwt=" + api.get_token(), enable_multithread=True, - timeout=1.0) - ws.settimeout(1) + timeout=30.0) cloudlog.event("athenad.main.connected_ws", ws_uri=ws_uri) manage_tokens(api) @@ -492,6 +496,8 @@ def main(): except (ConnectionError, TimeoutError, WebSocketException): conn_retries += 1 params.delete("LastAthenaPingTime") + if TICI: + cloudlog.exception("athenad.main.exception2") except Exception: cloudlog.exception("athenad.main.exception") diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index e52c8d2e6..c770845af 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -1,8 +1,4 @@ -#include #include -#include -#include -#include #include #include #include @@ -12,6 +8,10 @@ #include #include #include +#include +#include +#include +#include #include #include @@ -51,7 +51,7 @@ void safety_setter_thread() { // switch to SILENT when CarVin param is read while (true) { - if (do_exit || !panda->connected){ + if (do_exit || !panda->connected) { safety_setter_thread_running = false; return; }; @@ -67,12 +67,12 @@ void safety_setter_thread() { } // VIN query done, stop listening to OBDII - panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); + panda->set_safety_model(cereal::CarParams::SafetyModel::ELM327, 1); std::string params; LOGW("waiting for params to set safety model"); while (true) { - if (do_exit || !panda->connected){ + if (do_exit || !panda->connected) { safety_setter_thread_running = false; return; }; @@ -124,7 +124,7 @@ bool usb_connect() { // Convert to hex for offroad char fw_sig_hex_buf[16] = {0}; const uint8_t *fw_sig_buf = fw_sig->data(); - for (size_t i = 0; i < 8; i++){ + for (size_t i = 0; i < 8; i++) { fw_sig_hex_buf[2*i] = NIBBLE_TO_HEX((uint8_t)fw_sig_buf[i] >> 4); fw_sig_hex_buf[2*i+1] = NIBBLE_TO_HEX((uint8_t)fw_sig_buf[i] & 0xF); } @@ -146,7 +146,7 @@ bool usb_connect() { } #endif - if (tmp_panda->has_rtc){ + if (tmp_panda->has_rtc) { setenv("TZ","UTC",1); struct tm sys_time = util::get_time(); struct tm rtc_time = tmp_panda->get_rtc(); @@ -199,7 +199,7 @@ void can_send_thread(bool fake_send) { while (!do_exit && panda->connected) { Message * msg = subscriber->receive(); - if (!msg){ + if (!msg) { if (errno == EINTR) { do_exit = true; } @@ -211,7 +211,7 @@ void can_send_thread(bool fake_send) { //Dont send if older than 1 second if (nanos_since_boot() - event.getLogMonoTime() < 1e9) { - if (!fake_send){ + if (!fake_send) { panda->can_send(event.getSendcan()); } } @@ -241,7 +241,7 @@ void can_recv_thread() { if (remaining > 0) { std::this_thread::sleep_for(std::chrono::nanoseconds(remaining)); } else { - if (ignition){ + if (ignition) { LOGW("missed cycles (%d) %lld", (int)-1*remaining/dt, remaining); } next_frame_time = cur_time; @@ -292,7 +292,7 @@ void panda_state_thread(bool spoofing_started) { #ifndef __x86_64__ bool power_save_desired = !ignition; - if (pandaState.power_save_enabled != power_save_desired){ + if (pandaState.power_save_enabled != power_save_desired) { panda->set_power_saving(power_save_desired); } @@ -317,12 +317,12 @@ void panda_state_thread(bool spoofing_started) { } // Write to rtc once per minute when no ignition present - if ((panda->has_rtc) && !ignition && (no_ignition_cnt % 120 == 1)){ + if ((panda->has_rtc) && !ignition && (no_ignition_cnt % 120 == 1)) { // Write time to RTC if it looks reasonable setenv("TZ","UTC",1); struct tm sys_time = util::get_time(); - if (util::time_valid(sys_time)){ + if (util::time_valid(sys_time)) { struct tm rtc_time = panda->get_rtc(); double seconds = difftime(mktime(&rtc_time), mktime(&sys_time)); @@ -388,7 +388,7 @@ void panda_state_thread(bool spoofing_started) { size_t i = 0; for (size_t f = size_t(cereal::PandaState::FaultType::RELAY_MALFUNCTION); - f <= size_t(cereal::PandaState::FaultType::INTERRUPT_RATE_TIM9); f++){ + f <= size_t(cereal::PandaState::FaultType::INTERRUPT_RATE_TICK); f++) { if (fault_bits.test(f)) { faults.set(i, cereal::PandaState::FaultType(f)); i++; @@ -415,11 +415,11 @@ void hardware_control_thread() { cnt++; sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update? - if (!Hardware::PC() && sm.updated("deviceState")){ + if (!Hardware::PC() && sm.updated("deviceState")) { // Charging mode bool charging_disabled = sm["deviceState"].getDeviceState().getChargingDisabled(); - if (charging_disabled != prev_charging_disabled){ - if (charging_disabled){ + if (charging_disabled != prev_charging_disabled) { + if (charging_disabled) { panda->set_usb_power_mode(cereal::PandaState::UsbPowerMode::CLIENT); LOGW("TURN OFF CHARGING!\n"); } else { @@ -432,15 +432,15 @@ void hardware_control_thread() { // Other pandas don't have fan/IR to control if (panda->hw_type != cereal::PandaState::PandaType::UNO && panda->hw_type != cereal::PandaState::PandaType::DOS) continue; - if (sm.updated("deviceState")){ + if (sm.updated("deviceState")) { // Fan speed uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired(); - if (fan_speed != prev_fan_speed || cnt % 100 == 0){ + if (fan_speed != prev_fan_speed || cnt % 100 == 0) { panda->set_fan_speed(fan_speed); prev_fan_speed = fan_speed; } } - if (sm.updated("driverCameraState")){ + if (sm.updated("driverCameraState")) { auto event = sm["driverCameraState"]; int cur_integ_lines = event.getDriverCameraState().getIntegLines(); last_front_frame_t = event.getLogMonoTime(); @@ -455,11 +455,11 @@ void hardware_control_thread() { } // Disable ir_pwr on front frame timeout uint64_t cur_t = nanos_since_boot(); - if (cur_t - last_front_frame_t > 1e9){ + if (cur_t - last_front_frame_t > 1e9) { ir_pwr = 0; } - if (ir_pwr != prev_ir_pwr || cnt % 100 == 0 || ir_pwr >= 50.0){ + if (ir_pwr != prev_ir_pwr || cnt % 100 == 0 || ir_pwr >= 50.0) { panda->set_ir_pwr(ir_pwr); prev_ir_pwr = ir_pwr; } @@ -492,10 +492,10 @@ void pigeon_thread() { // Parse message header if (ignition && recv.length() >= 3) { - if (recv[0] == (char)ublox::PREAMBLE1 && recv[1] == (char)ublox::PREAMBLE2){ + if (recv[0] == (char)ublox::PREAMBLE1 && recv[1] == (char)ublox::PREAMBLE2) { const char msg_cls = recv[2]; uint64_t t = nanos_since_boot(); - if (t > last_recv_time[msg_cls]){ + if (t > last_recv_time[msg_cls]) { last_recv_time[msg_cls] = t; } } @@ -512,12 +512,12 @@ void pigeon_thread() { } // Check based on null bytes - if (ignition && recv.length() > 0 && recv[0] == (char)0x00){ + if (ignition && recv.length() > 0 && recv[0] == (char)0x00) { need_reset = true; LOGW("received invalid ublox message while onroad, resetting panda GPS"); } - if (recv.length() > 0){ + if (recv.length() > 0) { pigeon_publish_raw(pm, recv); } @@ -559,7 +559,7 @@ int main() { err = set_core_affinity(Hardware::TICI() ? 4 : 3); LOG("set affinity returns %d", err); - while (!do_exit){ + while (!do_exit) { std::vector threads; threads.push_back(std::thread(panda_state_thread, getenv("STARTED") != nullptr)); diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 1b563b53d..d75585065 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -11,7 +11,7 @@ #include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" -Panda::Panda(){ +Panda::Panda() { // init libusb int err = libusb_init(&ctx); if (err != 0) { goto fail; } @@ -50,14 +50,14 @@ fail: throw std::runtime_error("Error connecting to panda"); } -Panda::~Panda(){ +Panda::~Panda() { std::lock_guard lk(usb_lock); cleanup(); connected = false; } -void Panda::cleanup(){ - if (dev_handle){ +void Panda::cleanup() { + if (dev_handle) { libusb_release_interface(dev_handle, 0); libusb_close(dev_handle); } @@ -80,7 +80,7 @@ int Panda::usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigne int err; const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; - if (!connected){ + if (!connected) { return LIBUSB_ERROR_NO_DEVICE; } @@ -97,7 +97,7 @@ int Panda::usb_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int err; const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; - if (!connected){ + if (!connected) { return LIBUSB_ERROR_NO_DEVICE; } @@ -114,7 +114,7 @@ int Panda::usb_bulk_write(unsigned char endpoint, unsigned char* data, int lengt int err; int transferred = 0; - if (!connected){ + if (!connected) { return 0; } @@ -139,7 +139,7 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length int err; int transferred = 0; - if (!connected){ + if (!connected) { return 0; } @@ -162,7 +162,7 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length return transferred; } -void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, int safety_param){ +void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, int safety_param) { usb_write(0xdc, (uint16_t)safety_model, safety_param); } @@ -177,7 +177,7 @@ cereal::PandaState::PandaType Panda::get_hw_type() { return (cereal::PandaState::PandaType)(hw_query[0]); } -void Panda::set_rtc(struct tm sys_time){ +void Panda::set_rtc(struct tm sys_time) { // tm struct has year defined as years since 1900 usb_write(0xa1, (uint16_t)(1900 + sys_time.tm_year), 0); usb_write(0xa2, (uint16_t)(1 + sys_time.tm_mon), 0); @@ -188,7 +188,7 @@ void Panda::set_rtc(struct tm sys_time){ usb_write(0xa7, (uint16_t)sys_time.tm_sec, 0); } -struct tm Panda::get_rtc(){ +struct tm Panda::get_rtc() { struct __attribute__((packed)) timestamp_t { uint16_t year; // Starts at 0 uint8_t month; @@ -212,11 +212,11 @@ struct tm Panda::get_rtc(){ return new_time; } -void Panda::set_fan_speed(uint16_t fan_speed){ +void Panda::set_fan_speed(uint16_t fan_speed) { usb_write(0xb1, fan_speed, 0); } -uint16_t Panda::get_fan_speed(){ +uint16_t Panda::get_fan_speed() { uint16_t fan_speed_rpm = 0; usb_read(0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm)); return fan_speed_rpm; @@ -226,17 +226,17 @@ void Panda::set_ir_pwr(uint16_t ir_pwr) { usb_write(0xb0, ir_pwr, 0); } -health_t Panda::get_state(){ +health_t Panda::get_state() { health_t health {0}; usb_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health)); return health; } -void Panda::set_loopback(bool loopback){ +void Panda::set_loopback(bool loopback) { usb_write(0xe5, loopback, 0); } -std::optional> Panda::get_firmware_version(){ +std::optional> Panda::get_firmware_version() { std::vector fw_sig_buf(128); int read_1 = usb_read(0xd3, 0, 0, &fw_sig_buf[0], 64); int read_2 = usb_read(0xd4, 0, 0, &fw_sig_buf[64], 64); @@ -249,19 +249,19 @@ std::optional Panda::get_serial() { return err >= 0 ? std::make_optional(serial_buf) : std::nullopt; } -void Panda::set_power_saving(bool power_saving){ +void Panda::set_power_saving(bool power_saving) { usb_write(0xe7, power_saving, 0); } -void Panda::set_usb_power_mode(cereal::PandaState::UsbPowerMode power_mode){ +void Panda::set_usb_power_mode(cereal::PandaState::UsbPowerMode power_mode) { usb_write(0xe6, (uint16_t)power_mode, 0); } -void Panda::send_heartbeat(){ +void Panda::send_heartbeat() { usb_write(0xf3, 1, 0); } -void Panda::can_send(capnp::List::Reader can_data_list){ +void Panda::can_send(capnp::List::Reader can_data_list) { static std::vector send; const int msg_count = can_data_list.size(); diff --git a/selfdrive/boardd/pigeon.cc b/selfdrive/boardd/pigeon.cc index dc6a5e49a..002288c6e 100644 --- a/selfdrive/boardd/pigeon.cc +++ b/selfdrive/boardd/pigeon.cc @@ -1,11 +1,11 @@ #include "selfdrive/boardd/pigeon.h" -#include #include #include #include #include +#include #include #include "selfdrive/common/gpio.h" @@ -27,26 +27,26 @@ const std::string nack = "\xb5\x62\x05\x00\x02\x00"; const std::string sos_ack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x01\x00\x00\x00"; const std::string sos_nack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x00\x00\x00\x00"; -Pigeon * Pigeon::connect(Panda * p){ +Pigeon * Pigeon::connect(Panda * p) { PandaPigeon * pigeon = new PandaPigeon(); pigeon->connect(p); return pigeon; } -Pigeon * Pigeon::connect(const char * tty){ +Pigeon * Pigeon::connect(const char * tty) { TTYPigeon * pigeon = new TTYPigeon(); pigeon->connect(tty); return pigeon; } -bool Pigeon::wait_for_ack(std::string ack, std::string nack){ +bool Pigeon::wait_for_ack(const std::string &ack, const std::string &nack) { std::string s; - while (!do_exit){ + while (!do_exit) { s += receive(); - if (s.find(ack) != std::string::npos){ + if (s.find(ack) != std::string::npos) { LOGD("Received ACK from ublox"); return true; } else if (s.find(nack) != std::string::npos) { @@ -62,17 +62,17 @@ bool Pigeon::wait_for_ack(std::string ack, std::string nack){ return false; } -bool Pigeon::wait_for_ack(){ +bool Pigeon::wait_for_ack() { return wait_for_ack(ack, nack); } -bool Pigeon::send_with_ack(std::string cmd){ +bool Pigeon::send_with_ack(const std::string &cmd) { send(cmd); return wait_for_ack(); } void Pigeon::init() { - for (int i = 0; i < 10; i++){ + for (int i = 0; i < 10; i++) { if (do_exit) return; LOGW("panda GPS start"); @@ -118,7 +118,7 @@ void Pigeon::init() { if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x0A\x0B\x01\x20\x74"s)) continue; auto time = util::get_time(); - if (util::time_valid(time)){ + if (util::time_valid(time)) { LOGW("Sending current time to ublox"); send(ublox::build_ubx_mga_ini_time_utc(time)); } @@ -129,7 +129,7 @@ void Pigeon::init() { LOGE("failed to initialize panda GPS"); } -void Pigeon::stop(){ +void Pigeon::stop() { LOGW("Storing almanac in ublox flash"); // Controlled GNSS stop @@ -172,7 +172,7 @@ std::string PandaPigeon::receive() { std::string r; r.reserve(0x1000 + 0x40); unsigned char dat[0x40]; - while (r.length() < 0x1000){ + while (r.length() < 0x1000) { int len = panda->usb_read(0xe0, 1, 0, dat, sizeof(dat)); if (len <= 0) break; r.append((char*)dat, len); @@ -185,7 +185,7 @@ void PandaPigeon::set_power(bool power) { panda->usb_write(0xd9, power, 0); } -PandaPigeon::~PandaPigeon(){ +PandaPigeon::~PandaPigeon() { } void handle_tty_issue(int err, const char func[]) { @@ -194,7 +194,7 @@ void handle_tty_issue(int err, const char func[]) { void TTYPigeon::connect(const char * tty) { pigeon_tty_fd = open(tty, O_RDWR); - if (pigeon_tty_fd < 0){ + if (pigeon_tty_fd < 0) { handle_tty_issue(errno, __func__); assert(pigeon_tty_fd >= 0); } @@ -222,9 +222,9 @@ void TTYPigeon::connect(const char * tty) { assert(err == 0); } -void TTYPigeon::set_baud(int baud){ +void TTYPigeon::set_baud(int baud) { speed_t baud_const = 0; - switch(baud){ + switch(baud) { case 9600: baud_const = B9600; break; @@ -264,11 +264,11 @@ std::string TTYPigeon::receive() { std::string r; r.reserve(0x1000 + 0x40); char dat[0x40]; - while (r.length() < 0x1000){ + while (r.length() < 0x1000) { int len = read(pigeon_tty_fd, dat, sizeof(dat)); if(len < 0) { handle_tty_issue(len, __func__); - } else if (len == 0){ + } else if (len == 0) { break; } else { r.append(dat, len); @@ -278,7 +278,7 @@ std::string TTYPigeon::receive() { return r; } -void TTYPigeon::set_power(bool power){ +void TTYPigeon::set_power(bool power) { #ifdef QCOM2 int err = 0; err += gpio_init(GPIO_UBLOX_RST_N, true); @@ -292,6 +292,6 @@ void TTYPigeon::set_power(bool power){ #endif } -TTYPigeon::~TTYPigeon(){ +TTYPigeon::~TTYPigeon() { close(pigeon_tty_fd); } diff --git a/selfdrive/boardd/pigeon.h b/selfdrive/boardd/pigeon.h index ff22042dc..ecd42cb7b 100644 --- a/selfdrive/boardd/pigeon.h +++ b/selfdrive/boardd/pigeon.h @@ -16,8 +16,8 @@ class Pigeon { void init(); void stop(); bool wait_for_ack(); - bool wait_for_ack(std::string ack, std::string nack); - bool send_with_ack(std::string cmd); + bool wait_for_ack(const std::string &ack, const std::string &nack); + bool send_with_ack(const std::string &cmd); virtual void set_baud(int baud) = 0; virtual void send(const std::string &s) = 0; virtual std::string receive() = 0; diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index cf629bde3..125ac67a9 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -1,8 +1,9 @@ #include "selfdrive/camerad/cameras/camera_common.h" -#include -#include #include + +#include +#include #include #include @@ -124,8 +125,6 @@ bool CameraBuf::acquire() { const size_t globalWorkSize[] = {size_t(camera_state->ci.frame_width), size_t(camera_state->ci.frame_height)}; const size_t localWorkSize[] = {DEBAYER_LOCAL_WORKSIZE, DEBAYER_LOCAL_WORKSIZE}; CL_CHECK(clSetKernelArg(krnl_debayer, 2, localMemSize, 0)); - int ggain = camera_state->analog_gain + 4*camera_state->dc_gain_enabled; - CL_CHECK(clSetKernelArg(krnl_debayer, 3, sizeof(int), &ggain)); CL_CHECK(clEnqueueNDRangeKernel(q, krnl_debayer, 2, NULL, globalWorkSize, localWorkSize, 0, 0, &debayer_event)); #else @@ -162,7 +161,7 @@ bool CameraBuf::acquire() { } void CameraBuf::release() { - if (release_callback){ + if (release_callback) { release_callback((void*)camera_state, cur_buf_idx); } } @@ -179,12 +178,14 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr framed.setTimestampSof(frame_data.timestamp_sof); framed.setFrameLength(frame_data.frame_length); framed.setIntegLines(frame_data.integ_lines); - framed.setGlobalGain(frame_data.global_gain); + framed.setGain(frame_data.gain); + framed.setHighConversionGain(frame_data.high_conversion_gain); + framed.setMeasuredGreyFraction(frame_data.measured_grey_fraction); + framed.setTargetGreyFraction(frame_data.target_grey_fraction); framed.setLensPos(frame_data.lens_pos); framed.setLensSag(frame_data.lens_sag); framed.setLensErr(frame_data.lens_err); framed.setLensTruePos(frame_data.lens_true_pos); - framed.setGainFrac(frame_data.gain_frac); } kj::Array get_frame_image(const CameraBuf *b) { @@ -275,39 +276,30 @@ static void publish_thumbnail(PubMaster *pm, const CameraBuf *b) { free(thumbnail_buffer); } -float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip, int analog_gain, bool hist_ceil, bool hl_weighted) { - const uint8_t *pix_ptr = b->cur_yuv_buf->y; +float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip) { + int lum_med; uint32_t lum_binning[256] = {0}; + const uint8_t *pix_ptr = b->cur_yuv_buf->y; + unsigned int lum_total = 0; for (int y = y_start; y < y_end; y += y_skip) { for (int x = x_start; x < x_end; x += x_skip) { uint8_t lum = pix_ptr[(y * b->rgb_width) + x]; - if (hist_ceil && lum < 80 && lum_binning[lum] > HISTO_CEIL_K * (y_end - y_start) * (x_end - x_start) / x_skip / y_skip / 256) { - continue; - } lum_binning[lum]++; lum_total += 1; } } + + // Find mean lumimance value unsigned int lum_cur = 0; - int lum_med = 0; - int lum_med_alt = 0; - for (lum_med=255; lum_med>=0; lum_med--) { + for (lum_med = 255; lum_med >= 0; lum_med--) { lum_cur += lum_binning[lum_med]; - if (hl_weighted) { - int lum_med_tmp = 0; - int hb = HLC_THRESH + (10 - analog_gain); - if (lum_cur > 0 && lum_med > hb) { - lum_med_tmp = (lum_med - hb) + 100; - } - lum_med_alt = lum_med_alt>lum_med_tmp?lum_med_alt:lum_med_tmp; - } + if (lum_cur >= lum_total / 2) { break; } } - lum_med = lum_med_alt>0 ? lum_med + lum_med/32*lum_cur*abs(lum_med_alt - lum_med)/lum_total:lum_med; return lum_med / 256.0; } @@ -350,18 +342,12 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; const CameraBuf *b = &c->buf; - bool hist_ceil = false, hl_weighted = false; int x_offset = 0, y_offset = 0; int frame_width = b->rgb_width, frame_height = b->rgb_height; -#ifndef QCOM2 - int analog_gain = -1; -#else - int analog_gain = c->analog_gain; -#endif + ExpRect def_rect; if (Hardware::TICI()) { - hist_ceil = hl_weighted = true; x_offset = 630, y_offset = 156; frame_width = 668, frame_height = frame_width / 1.33; def_rect = {96, 1832, 2, 242, 1148, 4}; @@ -385,7 +371,7 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { } } - camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip, analog_gain, hist_ceil, hl_weighted)); + camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip)); } void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt) { diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index ab3efce28..8bf4ff336 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -1,8 +1,7 @@ #pragma once -#include -#include - +#include +#include #include #include @@ -28,7 +27,7 @@ #define CAMERA_ID_MAX 9 #define UI_BUF_COUNT 4 -#define YUV_COUNT 40 +#define YUV_COUNT 100 #define LOG_CAMERA_ID_FCAMERA 0 #define LOG_CAMERA_ID_DCAMERA 1 #define LOG_CAMERA_ID_ECAMERA 2 @@ -68,16 +67,24 @@ typedef struct LogCameraInfo { typedef struct FrameMetadata { uint32_t frame_id; + unsigned int frame_length; + + // Timestamps uint64_t timestamp_sof; // only set on tici uint64_t timestamp_eof; - unsigned int frame_length; + + // Exposure unsigned int integ_lines; - unsigned int global_gain; + bool high_conversion_gain; + float gain; + float measured_grey_fraction; + float target_grey_fraction; + + // Focus unsigned int lens_pos; float lens_sag; float lens_err; float lens_true_pos; - float gain_frac; } FrameMetadata; typedef struct CameraExpInfo { @@ -128,7 +135,7 @@ typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt); void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data); kj::Array get_frame_image(const CameraBuf *b); -float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip, int analog_gain, bool hist_ceil, bool hl_weighted); +float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip); std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt); diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc index a03feb132..8e6c69e36 100644 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ b/selfdrive/camerad/cameras/camera_frame_stream.cc @@ -50,15 +50,13 @@ void run_frame_stream(CameraState &camera, const char* frame_pkt) { size_t buf_idx = 0; while (!do_exit) { sm.update(1000); - if(sm.updated(frame_pkt)){ + if(sm.updated(frame_pkt)) { auto msg = static_cast(sm[frame_pkt]); auto frame = msg.get(frame_pkt).as(); camera.buf.camera_bufs_metadata[buf_idx] = { .frame_id = frame.get("frameId").as(), .timestamp_eof = frame.get("timestampEof").as(), - .frame_length = frame.get("frameLength").as(), - .integ_lines = frame.get("integLines").as(), - .global_gain = frame.get("globalGain").as(), + .timestamp_sof = frame.get("timestampSof").as(), }; cl_command_queue q = camera.buf.camera_bufs[buf_idx].copy_q; diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index aa386e5c8..7b350215d 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -1,15 +1,15 @@ #include "selfdrive/camerad/cameras/camera_qcom.h" -#include #include -#include #include -#include #include #include #include #include +#include +#include +#include #include #include @@ -282,6 +282,12 @@ static void set_exposure(CameraState *s, float exposure_frac, float gain_frac) { static void do_autoexposure(CameraState *s, float grey_frac) { const float target_grey = 0.3; + + s->frame_info_lock.lock(); + s->measured_grey_fraction = grey_frac; + s->target_grey_fraction = target_grey; + s->frame_info_lock.unlock(); + if (s->apply_exposure == ov8865_apply_exposure) { // gain limits downstream const float gain_frac_min = 0.015625; @@ -848,7 +854,7 @@ static void parse_autofocus(CameraState *s, uint8_t *d) { static std::optional get_accel_z(SubMaster *sm) { sm->update(0); - if(sm->updated("sensorEvents")){ + if(sm->updated("sensorEvents")) { for (auto event : (*sm)["sensorEvents"].getSensorEvents()) { if (event.which() == cereal::SensorEventData::ACCELERATION) { if (auto v = event.getAcceleration().getV(); v.size() >= 3) @@ -1107,7 +1113,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { if (cnt % 3 == 0) { const int x = 290, y = 322, width = 560, height = 314; const int skip = 1; - camera_autoexposure(c, set_exposure_target(b, x, x + width, skip, y, y + height, skip, -1, false, false)); + camera_autoexposure(c, set_exposure_target(b, x, x + width, skip, y, y + height, skip)); } } @@ -1162,12 +1168,14 @@ void cameras_run(MultiCameraState *s) { .timestamp_eof = timestamp, .frame_length = (uint32_t)c->frame_length, .integ_lines = (uint32_t)c->cur_integ_lines, - .global_gain = (uint32_t)c->cur_gain, .lens_pos = c->cur_lens_pos, .lens_sag = c->last_sag_acc_z, .lens_err = c->focus_err, .lens_true_pos = c->lens_true_pos, - .gain_frac = c->cur_gain_frac, + .gain = c->cur_gain_frac, + .measured_grey_fraction = c->measured_grey_fraction, + .target_grey_fraction = c->target_grey_fraction, + .high_conversion_gain = false, }; c->frame_metadata_idx = (c->frame_metadata_idx + 1) % METADATA_BUF_COUNT; diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h index 1bcfed205..207857e05 100644 --- a/selfdrive/camerad/cameras/camera_qcom.h +++ b/selfdrive/camerad/cameras/camera_qcom.h @@ -1,8 +1,7 @@ #pragma once -#include - #include +#include #include #include "cereal/messaging/messaging.h" @@ -67,6 +66,10 @@ typedef struct CameraState { unsigned int max_gain; float cur_exposure_frac, cur_gain_frac; int cur_gain, cur_integ_lines; + + float measured_grey_fraction; + float target_grey_fraction; + std::atomic digital_gain; camera_apply_exposure_func apply_exposure; diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc deleted file mode 100644 index 44f77d80b..000000000 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ /dev/null @@ -1,1138 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "media/cam_defs.h" -#include "media/cam_isp.h" -#include "media/cam_isp_ife.h" -#include "media/cam_sensor_cmn_header.h" -#include "media/cam_sensor.h" -#include "media/cam_sync.h" -#include "sensor2_i2c.h" - -#include "selfdrive/common/swaglog.h" -#include "selfdrive/camerad/cameras/camera_qcom2.h" - -#define FRAME_WIDTH 1928 -#define FRAME_HEIGHT 1208 -//#define FRAME_STRIDE 1936 // for 8 bit output -#define FRAME_STRIDE 2416 // for 10 bit output - -#define MIPI_SETTLE_CNT 33 // Calculated by camera_freqs.py - -extern ExitHandler do_exit; - -// global var for AE ops -std::atomic cam_exp[3] = {{{0}}}; - -CameraInfo cameras_supported[CAMERA_ID_MAX] = { - [CAMERA_ID_AR0231] = { - .frame_width = FRAME_WIDTH, - .frame_height = FRAME_HEIGHT, - .frame_stride = FRAME_STRIDE, - .bayer = true, - .bayer_flip = 1, - .hdr = false - }, -}; - -float sensor_analog_gains[ANALOG_GAIN_MAX_IDX] = {3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, - 5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, - 7.0/2.0, 8.0/2.0}; - -// ************** low level camera helpers **************** - -int cam_control(int fd, int op_code, void *handle, int size) { - struct cam_control camcontrol = {0}; - camcontrol.op_code = op_code; - camcontrol.handle = (uint64_t)handle; - if (size == 0) { camcontrol.size = 8; - camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; - } else { - camcontrol.size = size; - camcontrol.handle_type = CAM_HANDLE_USER_POINTER; - } - - int ret = ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol); - if (ret == -1) { - printf("OP CODE ERR - %d \n", op_code); - perror("wat"); - } - return ret; -} - -int device_control(int fd, int op_code, int session_handle, int dev_handle) { - // start stop and release are all the same - static struct cam_release_dev_cmd release_dev_cmd; - release_dev_cmd.session_handle = session_handle; - release_dev_cmd.dev_handle = dev_handle; - return cam_control(fd, op_code, &release_dev_cmd, sizeof(release_dev_cmd)); -} - -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, - int mmu_hdl = 0, int mmu_hdl2 = 0) { - struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; - mem_mgr_alloc_cmd.len = len; - mem_mgr_alloc_cmd.align = align; - mem_mgr_alloc_cmd.flags = flags; - mem_mgr_alloc_cmd.num_hdl = 0; - if (mmu_hdl != 0) { - mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; - mem_mgr_alloc_cmd.num_hdl++; - } - if (mmu_hdl2 != 0) { - mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; - mem_mgr_alloc_cmd.num_hdl++; - } - - cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); - *handle = mem_mgr_alloc_cmd.out.buf_handle; - - void *ptr = NULL; - if (mem_mgr_alloc_cmd.out.fd > 0) { - ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); - assert(ptr != MAP_FAILED); - } - - // LOGD("alloced: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); - - return ptr; -} - -void release(int video0_fd, uint32_t handle) { - int ret; - struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; - mem_mgr_release_cmd.buf_handle = handle; - - ret = cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); - assert(ret == 0); -} - -void release_fd(int video0_fd, uint32_t handle) { - // handle to fd - close(handle>>16); - release(video0_fd, handle); -} - -void clear_req_queue(int fd, int32_t session_hdl, int32_t link_hdl) { - struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; - req_mgr_flush_request.session_hdl = session_hdl; - req_mgr_flush_request.link_hdl = link_hdl; - req_mgr_flush_request.flush_type = CAM_REQ_MGR_FLUSH_TYPE_ALL; - int ret; - ret = cam_control(fd, CAM_REQ_MGR_FLUSH_REQ, &req_mgr_flush_request, sizeof(req_mgr_flush_request)); - // LOGD("flushed all req: %d", ret); -} - -// ************** high level camera helpers **************** - -void sensors_poke(struct CameraState *s, int request_id) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet); - struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, size, &cam_packet_handle); - pkt->num_cmd_buf = 0; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = 0x7f; - pkt->header.request_id = request_id; - - struct cam_config_dev_cmd config_dev_cmd = {}; - config_dev_cmd.session_handle = s->session_handle; - config_dev_cmd.dev_handle = s->sensor_dev_handle; - config_dev_cmd.offset = 0; - config_dev_cmd.packet_handle = cam_packet_handle; - - int ret = cam_control(s->sensor_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd)); - assert(ret == 0); - - munmap(pkt, size); - release_fd(s->multi_cam_state->video0_fd, cam_packet_handle); -} - -void sensors_i2c(struct CameraState *s, struct i2c_random_wr_payload* dat, int len, int op_code) { - // LOGD("sensors_i2c: %d", len); - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; - struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = op_code; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload); - buf_desc[0].type = CAM_CMD_BUF_I2C; - - struct cam_cmd_i2c_random_wr *i2c_random_wr = (struct cam_cmd_i2c_random_wr *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - i2c_random_wr->header.count = len; - i2c_random_wr->header.op_code = 1; - i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR; - i2c_random_wr->header.data_type = CAMERA_SENSOR_I2C_TYPE_WORD; - i2c_random_wr->header.addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - memcpy(i2c_random_wr->random_wr_payload, dat, len*sizeof(struct i2c_random_wr_payload)); - - struct cam_config_dev_cmd config_dev_cmd = {}; - config_dev_cmd.session_handle = s->session_handle; - config_dev_cmd.dev_handle = s->sensor_dev_handle; - config_dev_cmd.offset = 0; - config_dev_cmd.packet_handle = cam_packet_handle; - - int ret = cam_control(s->sensor_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd)); - assert(ret == 0); - - munmap(i2c_random_wr, buf_desc[0].size); - release_fd(s->multi_cam_state->video0_fd, buf_desc[0].mem_handle); - munmap(pkt, size); - release_fd(s->multi_cam_state->video0_fd, cam_packet_handle); -} -static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { - cam_cmd_unconditional_wait *unconditional_wait = (cam_cmd_unconditional_wait *)((char *)power + (sizeof(struct cam_cmd_power) + (power->count - 1) * sizeof(struct cam_power_settings))); - unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; - unconditional_wait->delay = delay_ms; - unconditional_wait->op_code = CAMERA_SENSOR_WAIT_OP_SW_UCND; - return (struct cam_cmd_power *)(unconditional_wait + 1); -}; - -void sensors_init(int video0_fd, int sensor_fd, int camera_num) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(video0_fd, size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = -1; - pkt->header.op_code = 0x1000003; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); - buf_desc[0].type = CAM_CMD_BUF_LEGACY; - struct cam_cmd_i2c_info *i2c_info = (struct cam_cmd_i2c_info *)alloc_w_mmu_hdl(video0_fd, buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - struct cam_cmd_probe *probe = (struct cam_cmd_probe *)((uint8_t *)i2c_info) + sizeof(struct cam_cmd_i2c_info); - - switch (camera_num) { - case 0: - // port 0 - i2c_info->slave_addr = 0x20; - probe->camera_id = 0; - break; - case 1: - // port 1 - i2c_info->slave_addr = 0x30; - probe->camera_id = 1; - break; - case 2: - // port 2 - i2c_info->slave_addr = 0x20; - probe->camera_id = 2; - break; - } - - // 0(I2C_STANDARD_MODE) = 100khz, 1(I2C_FAST_MODE) = 400khz - //i2c_info->i2c_freq_mode = I2C_STANDARD_MODE; - i2c_info->i2c_freq_mode = I2C_FAST_MODE; - i2c_info->cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_INFO; - - probe->data_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->op_code = 3; // don't care? - probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; - probe->reg_addr = 0x3000; //0x300a; //0x300b; - probe->expected_data = 0x354; //0x7750; //0x885a; - probe->data_mask = 0; - - //buf_desc[1].size = buf_desc[1].length = 148; - buf_desc[1].size = buf_desc[1].length = 196; - buf_desc[1].type = CAM_CMD_BUF_I2C; - struct cam_cmd_power *power_settings = (struct cam_cmd_power *)alloc_w_mmu_hdl(video0_fd, buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - memset(power_settings, 0, buf_desc[1].size); - // 7750 - /*power->count = 2; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 2; - power->power_settings[1].power_seq_type = 8; - power = (void*)power + (sizeof(struct cam_cmd_power) + (power->count-1)*sizeof(struct cam_power_settings));*/ - - // 885a - struct cam_cmd_power *power = power_settings; - power->count = 4; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 3; // clock?? - power->power_settings[1].power_seq_type = 1; // analog - power->power_settings[2].power_seq_type = 2; // digital - power->power_settings[3].power_seq_type = 8; // reset low - power = power_set_wait(power, 5); - - // set clock - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = 19200000; //Hz - power = power_set_wait(power, 10); - - // 8,1 is this reset? - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - power = power_set_wait(power, 100); - - // probe happens here - - // disable clock - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // reset high - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - power = power_set_wait(power, 1); - - // reset low - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // 7750 - /*power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 2; - power = (void*)power + (sizeof(struct cam_cmd_power) + (power->count-1)*sizeof(struct cam_power_settings));*/ - - // 885a - power->count = 3; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 2; - power->power_settings[1].power_seq_type = 1; - power->power_settings[2].power_seq_type = 3; - - LOGD("probing the sensor"); - int ret = cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); - assert(ret == 0); - - munmap(i2c_info, buf_desc[0].size); - release_fd(video0_fd, buf_desc[0].mem_handle); - munmap(power_settings, buf_desc[1].size); - release_fd(video0_fd, buf_desc[1].mem_handle); - munmap(pkt, size); - release_fd(video0_fd, cam_packet_handle); -} - -void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - if (io_mem_handle != 0) { - size += sizeof(struct cam_buf_io_cfg); - } - struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = 0; - - if (io_mem_handle != 0) { - pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*2; - pkt->num_io_configs = 1; - } - - if (io_mem_handle != 0) { - pkt->header.op_code = 0xf000001; - pkt->header.request_id = request_id; - } else { - pkt->header.op_code = 0xf000000; - } - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); - - // TODO: support MMU - buf_desc[0].size = 65624; - buf_desc[0].length = 0; - buf_desc[0].type = CAM_CMD_BUF_DIRECT; - buf_desc[0].meta_data = 3; - buf_desc[0].mem_handle = buf0_mem_handle; - buf_desc[0].offset = buf0_offset; - - buf_desc[1].size = 324; - if (io_mem_handle != 0) { - buf_desc[1].length = 228; // 0 works here too - buf_desc[1].offset = 0x60; - } else { - buf_desc[1].length = 324; - } - buf_desc[1].type = CAM_CMD_BUF_GENERIC; - buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; - uint32_t *buf2 = (uint32_t *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle, 0x20); - - // cam_isp_packet_generic_blob_handler - uint32_t tmp[] = { - // size is 0x20, type is 0(CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG) - 0x2000, - 0x1, 0x0, CAM_ISP_IFE_OUT_RES_RDI_0, 0x1, 0x0, 0x1, 0x0, 0x0, // 1 port, CAM_ISP_IFE_OUT_RES_RDI_0 - // size is 0x38, type is 1(CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG), clocks - 0x3801, - 0x1, 0x4, // Dual mode, 4 RDI wires - 0x18148d00, 0x0, 0x18148d00, 0x0, 0x18148d00, 0x0, // rdi clock - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, // junk? - // offset 0x60 - // size is 0xe0, type is 2(CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG), bandwidth - 0xe002, - 0x1, 0x4, // 4 RDI - 0x0, 0x0, 0x1ad27480, 0x0, 0x1ad27480, 0x0, // left_pix_vote - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, // right_pix_vote - 0x0, 0x0, 0x6ee11c0, 0x2, 0x6ee11c0, 0x2, // rdi_vote - 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}; - memcpy(buf2, tmp, sizeof(tmp)); - - if (io_mem_handle != 0) { - io_cfg[0].mem_handle[0] = io_mem_handle; - io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = FRAME_WIDTH, - .height = FRAME_HEIGHT, - .plane_stride = FRAME_STRIDE, - .slice_height = FRAME_HEIGHT, - .meta_stride = 0x0, - .meta_size = 0x0, - .meta_offset = 0x0, - .packer_config = 0x0, - .mode_config = 0x0, - .tile_config = 0x0, - .h_init = 0x0, - .v_init = 0x0, - }; - io_cfg[0].format = CAM_FORMAT_MIPI_RAW_10; - io_cfg[0].color_pattern = 0x5; - io_cfg[0].bpp = 0xc; - io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; - io_cfg[0].fence = fence; - io_cfg[0].direction = CAM_BUF_OUTPUT; - io_cfg[0].subsample_pattern = 0x1; - io_cfg[0].framedrop_pattern = 0x1; - } - - struct cam_config_dev_cmd config_dev_cmd = {}; - config_dev_cmd.session_handle = s->session_handle; - config_dev_cmd.dev_handle = s->isp_dev_handle; - config_dev_cmd.offset = 0; - config_dev_cmd.packet_handle = cam_packet_handle; - - int ret = cam_control(s->multi_cam_state->isp_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd)); - if (ret != 0) { - printf("ISP CONFIG FAILED\n"); - } - - munmap(buf2, buf_desc[1].size); - release_fd(s->multi_cam_state->video0_fd, buf_desc[1].mem_handle); - // release_fd(s->multi_cam_state->video0_fd, buf_desc[0].mem_handle); - munmap(pkt, size); - release_fd(s->multi_cam_state->video0_fd, cam_packet_handle); -} - -void enqueue_buffer(struct CameraState *s, int i, bool dp) { - int ret; - int request_id = s->request_ids[i]; - - if (s->buf_handle[i]) { - release(s->multi_cam_state->video0_fd, s->buf_handle[i]); - // wait - struct cam_sync_wait sync_wait = {0}; - sync_wait.sync_obj = s->sync_objs[i]; - sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23 - ret = cam_control(s->multi_cam_state->video1_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait)); - // LOGD("fence wait: %d %d", ret, sync_wait.sync_obj); - - s->buf.camera_bufs_metadata[i].timestamp_eof = (uint64_t)nanos_since_boot(); // set true eof - if (dp) s->buf.queue(i); - - // destroy old output fence - struct cam_sync_info sync_destroy = {0}; - strcpy(sync_destroy.name, "NodeOutputPortFence"); - sync_destroy.sync_obj = s->sync_objs[i]; - ret = cam_control(s->multi_cam_state->video1_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy)); - // LOGD("fence destroy: %d %d", ret, sync_destroy.sync_obj); - } - - // do stuff - struct cam_req_mgr_sched_request req_mgr_sched_request = {0}; - req_mgr_sched_request.session_hdl = s->session_handle; - req_mgr_sched_request.link_hdl = s->link_handle; - req_mgr_sched_request.req_id = request_id; - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request)); - // LOGD("sched req: %d %d", ret, request_id); - - // create output fence - struct cam_sync_info sync_create = {0}; - strcpy(sync_create.name, "NodeOutputPortFence"); - ret = cam_control(s->multi_cam_state->video1_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create)); - // LOGD("fence req: %d %d", ret, sync_create.sync_obj); - s->sync_objs[i] = sync_create.sync_obj; - - // configure ISP to put the image in place - struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; - mem_mgr_map_cmd.mmu_hdls[0] = s->multi_cam_state->device_iommu; - mem_mgr_map_cmd.num_hdl = 1; - mem_mgr_map_cmd.flags = 1; - mem_mgr_map_cmd.fd = s->buf.camera_bufs[i].fd; - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); - // LOGD("map buf req: (fd: %d) 0x%x %d", s->bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); - s->buf_handle[i] = mem_mgr_map_cmd.out.buf_handle; - - // poke sensor - sensors_poke(s, request_id); - // LOGD("Poked sensor"); - - // push the buffer - config_isp(s, s->buf_handle[i], s->sync_objs[i], request_id, s->buf0_handle, 65632*(i+1)); -} - -void enqueue_req_multi(struct CameraState *s, int start, int n, bool dp) { - for (int i=start;irequest_ids[(i - 1) % FRAME_BUF_COUNT] = i; - enqueue_buffer(s, (i - 1) % FRAME_BUF_COUNT, dp); - } -} - -// ******************* camera ******************* - -static void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v, CameraState *s, int camera_id, int camera_num, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType rgb_type, VisionStreamType yuv_type) { - LOGD("camera init %d", camera_num); - s->multi_cam_state = multi_cam_state; - assert(camera_id < std::size(cameras_supported)); - s->ci = cameras_supported[camera_id]; - assert(s->ci.frame_width != 0); - - s->camera_num = camera_num; - - s->dc_gain_enabled = false; - s->analog_gain = 0x5; - s->analog_gain_frac = sensor_analog_gains[s->analog_gain]; - s->exposure_time = 256; - s->exposure_time_max = 1.2 * EXPOSURE_TIME_MAX / 2; - s->exposure_time_min = 0.75 * EXPOSURE_TIME_MIN * 2; - s->request_id_last = 0; - s->skipped = true; - s->ef_filtered = 1.0; - - s->buf.init(device_id, ctx, s, v, FRAME_BUF_COUNT, rgb_type, yuv_type); -} - -// TODO: refactor this to somewhere nicer, perhaps use in camera_qcom as well -static int open_v4l_by_name_and_index(const char name[], int index, int flags) { - char nbuf[0x100]; - int v4l_index = 0; - int cnt_index = index; - while (1) { - snprintf(nbuf, sizeof(nbuf), "/sys/class/video4linux/v4l-subdev%d/name", v4l_index); - FILE *f = fopen(nbuf, "rb"); - if (f == NULL) return -1; - int len = fread(nbuf, 1, sizeof(nbuf), f); - fclose(f); - - // name ends with '\n', remove it - if (len < 1) return -1; - nbuf[len-1] = '\0'; - - if (strcmp(nbuf, name) == 0) { - if (cnt_index == 0) { - snprintf(nbuf, sizeof(nbuf), "/dev/v4l-subdev%d", v4l_index); - LOGD("open %s for %s index %d", nbuf, name, index); - return open(nbuf, flags); - } - cnt_index--; - } - v4l_index++; - } -} - -static void camera_open(CameraState *s) { - int ret; - s->sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", s->camera_num, O_RDWR | O_NONBLOCK); - assert(s->sensor_fd >= 0); - LOGD("opened sensor"); - - s->csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", s->camera_num, O_RDWR | O_NONBLOCK); - assert(s->csiphy_fd >= 0); - LOGD("opened csiphy"); - - // probe the sensor - LOGD("-- Probing sensor %d", s->camera_num); - sensors_init(s->multi_cam_state->video0_fd, s->sensor_fd, s->camera_num); - - memset(&s->req_mgr_session_info, 0, sizeof(s->req_mgr_session_info)); - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &s->req_mgr_session_info, sizeof(s->req_mgr_session_info)); - LOGD("get session: %d 0x%X", ret, s->req_mgr_session_info.session_hdl); - s->session_handle = s->req_mgr_session_info.session_hdl; - // access the sensor - LOGD("-- Accessing sensor"); - static struct cam_acquire_dev_cmd acquire_dev_cmd = {0}; - acquire_dev_cmd.session_handle = s->session_handle; - acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER; - ret = cam_control(s->sensor_fd, CAM_ACQUIRE_DEV, &acquire_dev_cmd, sizeof(acquire_dev_cmd)); - LOGD("acquire sensor dev: %d", ret); - s->sensor_dev_handle = acquire_dev_cmd.dev_handle; - - static struct cam_isp_resource isp_resource = {0}; - - acquire_dev_cmd.session_handle = s->session_handle; - acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER; - acquire_dev_cmd.num_resources = 1; - acquire_dev_cmd.resource_hdl = (uint64_t)&isp_resource; - - isp_resource.resource_id = CAM_ISP_RES_ID_PORT; - isp_resource.length = sizeof(struct cam_isp_in_port_info) + sizeof(struct cam_isp_out_port_info)*(1-1); - isp_resource.handle_type = CAM_HANDLE_USER_POINTER; - - struct cam_isp_in_port_info *in_port_info = (struct cam_isp_in_port_info *)malloc(isp_resource.length); - isp_resource.res_hdl = (uint64_t)in_port_info; - - switch (s->camera_num) { - case 0: - in_port_info->res_type = CAM_ISP_IFE_IN_RES_PHY_0; - break; - case 1: - in_port_info->res_type = CAM_ISP_IFE_IN_RES_PHY_1; - break; - case 2: - in_port_info->res_type = CAM_ISP_IFE_IN_RES_PHY_2; - break; - } - - in_port_info->lane_type = CAM_ISP_LANE_TYPE_DPHY; - in_port_info->lane_num = 4; - in_port_info->lane_cfg = 0x3210; - - in_port_info->vc = 0x0; - //in_port_info->dt = 0x2C; //CSI_RAW12 - //in_port_info->format = CAM_FORMAT_MIPI_RAW_12; - - in_port_info->dt = 0x2B; //CSI_RAW10 - in_port_info->format = CAM_FORMAT_MIPI_RAW_10; - - in_port_info->test_pattern = 0x2; // 0x3? - in_port_info->usage_type = 0x0; - - in_port_info->left_start = 0x0; - in_port_info->left_stop = FRAME_WIDTH - 1; - in_port_info->left_width = FRAME_WIDTH; - - in_port_info->right_start = 0x0; - in_port_info->right_stop = FRAME_WIDTH - 1; - in_port_info->right_width = FRAME_WIDTH; - - in_port_info->line_start = 0x0; - in_port_info->line_stop = FRAME_HEIGHT - 1; - in_port_info->height = FRAME_HEIGHT; - - in_port_info->pixel_clk = 0x0; - in_port_info->batch_size = 0x0; - in_port_info->dsp_mode = 0x0; - in_port_info->hbi_cnt = 0x0; - in_port_info->custom_csid = 0x0; - - in_port_info->num_out_res = 0x1; - in_port_info->data[0] = (struct cam_isp_out_port_info){ - .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, - //.format = CAM_FORMAT_MIPI_RAW_12, - .format = CAM_FORMAT_MIPI_RAW_10, - .width = FRAME_WIDTH, - .height = FRAME_HEIGHT, - .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, - }; - - ret = cam_control(s->multi_cam_state->isp_fd, CAM_ACQUIRE_DEV, &acquire_dev_cmd, sizeof(acquire_dev_cmd)); - LOGD("acquire isp dev: %d", ret); - free(in_port_info); - s->isp_dev_handle = acquire_dev_cmd.dev_handle; - - static struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {0}; - csiphy_acquire_dev_info.combo_mode = 0; - - acquire_dev_cmd.session_handle = s->session_handle; - acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER; - acquire_dev_cmd.num_resources = 1; - acquire_dev_cmd.resource_hdl = (uint64_t)&csiphy_acquire_dev_info; - - ret = cam_control(s->csiphy_fd, CAM_ACQUIRE_DEV, &acquire_dev_cmd, sizeof(acquire_dev_cmd)); - - LOGD("acquire csiphy dev: %d", ret); - s->csiphy_dev_handle = acquire_dev_cmd.dev_handle; - - // acquires done - - // config ISP - alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, 984480, (uint32_t*)&s->buf0_handle, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, s->multi_cam_state->device_iommu, s->multi_cam_state->cdm_iommu); - config_isp(s, 0, 0, 1, s->buf0_handle, 0); - - LOG("-- Configuring sensor"); - sensors_i2c(s, init_array_ar0231, sizeof(init_array_ar0231)/sizeof(struct i2c_random_wr_payload), - CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); - //sensors_i2c(s, start_reg_array, sizeof(start_reg_array)/sizeof(struct i2c_random_wr_payload), - //CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMON); - //sensors_i2c(s, stop_reg_array, sizeof(stop_reg_array)/sizeof(struct i2c_random_wr_payload), - //CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMOFF); - - // config csiphy - LOG("-- Config CSI PHY"); - { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; - struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); - buf_desc[0].type = CAM_CMD_BUF_GENERIC; - - struct cam_csiphy_info *csiphy_info = (struct cam_csiphy_info *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - csiphy_info->lane_mask = 0x1f; - csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? - csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane - csiphy_info->combo_mode = 0x0; - csiphy_info->lane_cnt = 0x4; - csiphy_info->secure_mode = 0x0; - csiphy_info->settle_time = MIPI_SETTLE_CNT * 200000000ULL; - csiphy_info->data_rate = 48000000; // Calculated by camera_freqs.py - - static struct cam_config_dev_cmd config_dev_cmd = {}; - config_dev_cmd.session_handle = s->session_handle; - config_dev_cmd.dev_handle = s->csiphy_dev_handle; - config_dev_cmd.offset = 0; - config_dev_cmd.packet_handle = cam_packet_handle; - - int ret = cam_control(s->csiphy_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd)); - assert(ret == 0); - - release(s->multi_cam_state->video0_fd, buf_desc[0].mem_handle); - release(s->multi_cam_state->video0_fd, cam_packet_handle); - } - - // link devices - LOG("-- Link devices"); - static struct cam_req_mgr_link_info req_mgr_link_info = {0}; - req_mgr_link_info.session_hdl = s->session_handle; - req_mgr_link_info.num_devices = 2; - req_mgr_link_info.dev_hdls[0] = s->isp_dev_handle; - req_mgr_link_info.dev_hdls[1] = s->sensor_dev_handle; - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_LINK, &req_mgr_link_info, sizeof(req_mgr_link_info)); - LOGD("link: %d", ret); - s->link_handle = req_mgr_link_info.link_hdl; - - static struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = 0; - req_mgr_link_control.session_hdl = s->session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = s->link_handle; - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control: %d", ret); - - LOGD("start csiphy: %d", ret); - ret = device_control(s->csiphy_fd, CAM_START_DEV, s->session_handle, s->csiphy_dev_handle); - LOGD("start isp: %d", ret); - ret = device_control(s->multi_cam_state->isp_fd, CAM_START_DEV, s->session_handle, s->isp_dev_handle); - LOGD("start sensor: %d", ret); - ret = device_control(s->sensor_fd, CAM_START_DEV, s->session_handle, s->sensor_dev_handle); - - enqueue_req_multi(s, 1, FRAME_BUF_COUNT, 0); -} - -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - camera_init(s, v, &s->road_cam, CAMERA_ID_AR0231, 1, 20, device_id, ctx, - VISION_STREAM_RGB_BACK, VISION_STREAM_YUV_BACK); // swap left/right - printf("road camera initted \n"); - camera_init(s, v, &s->wide_road_cam, CAMERA_ID_AR0231, 0, 20, device_id, ctx, - VISION_STREAM_RGB_WIDE, VISION_STREAM_YUV_WIDE); - printf("wide road camera initted \n"); - camera_init(s, v, &s->driver_cam, CAMERA_ID_AR0231, 2, 20, device_id, ctx, - VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV_FRONT); - printf("driver camera initted \n"); - - s->sm = new SubMaster({"driverState"}); - s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); -} - -void cameras_open(MultiCameraState *s) { - int ret; - - LOG("-- Opening devices"); - // video0 is req_mgr, the target of many ioctls - s->video0_fd = open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK); - assert(s->video0_fd >= 0); - LOGD("opened video0"); - - // video1 is cam_sync, the target of some ioctls - s->video1_fd = open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK); - assert(s->video1_fd >= 0); - LOGD("opened video1"); - - // looks like there's only one of these - s->isp_fd = open("/dev/v4l-subdev1", O_RDWR | O_NONBLOCK); - assert(s->isp_fd >= 0); - LOGD("opened isp"); - - // query icp for MMU handles - LOG("-- Query ICP for MMU handles"); - static struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; - static struct cam_query_cap_cmd query_cap_cmd = {0}; - query_cap_cmd.handle_type = 1; - query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd; - query_cap_cmd.size = sizeof(isp_query_cap_cmd); - ret = cam_control(s->isp_fd, CAM_QUERY_CAP, &query_cap_cmd, sizeof(query_cap_cmd)); - assert(ret == 0); - LOGD("using MMU handle: %x", isp_query_cap_cmd.device_iommu.non_secure); - LOGD("using MMU handle: %x", isp_query_cap_cmd.cdm_iommu.non_secure); - s->device_iommu = isp_query_cap_cmd.device_iommu.non_secure; - s->cdm_iommu = isp_query_cap_cmd.cdm_iommu.non_secure; - - // subscribe - LOG("-- Subscribing"); - static struct v4l2_event_subscription sub = {0}; - sub.type = 0x8000000; - sub.id = 2; // should use boot time for sof - ret = ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub); - printf("req mgr subscribe: %d\n", ret); - - camera_open(&s->road_cam); - printf("road camera opened \n"); - camera_open(&s->wide_road_cam); - printf("wide road camera opened \n"); - camera_open(&s->driver_cam); - printf("driver camera opened \n"); -} - -static void camera_close(CameraState *s) { - int ret; - - // stop devices - LOG("-- Stop devices"); - // ret = device_control(s->sensor_fd, CAM_STOP_DEV, s->session_handle, s->sensor_dev_handle); - // LOGD("stop sensor: %d", ret); - ret = device_control(s->multi_cam_state->isp_fd, CAM_STOP_DEV, s->session_handle, s->isp_dev_handle); - LOGD("stop isp: %d", ret); - ret = device_control(s->csiphy_fd, CAM_STOP_DEV, s->session_handle, s->csiphy_dev_handle); - LOGD("stop csiphy: %d", ret); - // link control stop - LOG("-- Stop link control"); - static struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = 1; - req_mgr_link_control.session_hdl = s->session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = s->link_handle; - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control stop: %d", ret); - - // unlink - LOG("-- Unlink"); - static struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; - req_mgr_unlink_info.session_hdl = s->session_handle; - req_mgr_unlink_info.link_hdl = s->link_handle; - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info)); - LOGD("unlink: %d", ret); - - // release devices - LOGD("-- Release devices"); - ret = device_control(s->sensor_fd, CAM_RELEASE_DEV, s->session_handle, s->sensor_dev_handle); - LOGD("release sensor: %d", ret); - ret = device_control(s->multi_cam_state->isp_fd, CAM_RELEASE_DEV, s->session_handle, s->isp_dev_handle); - LOGD("release isp: %d", ret); - ret = device_control(s->csiphy_fd, CAM_RELEASE_DEV, s->session_handle, s->csiphy_dev_handle); - LOGD("release csiphy: %d", ret); - - ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &s->req_mgr_session_info, sizeof(s->req_mgr_session_info)); - LOGD("destroyed session: %d", ret); -} - -void cameras_close(MultiCameraState *s) { - camera_close(&s->road_cam); - camera_close(&s->wide_road_cam); - camera_close(&s->driver_cam); - - delete s->sm; - delete s->pm; -} - -// ******************* just a helper ******************* - -void handle_camera_event(CameraState *s, void *evdat) { - struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; - - uint64_t timestamp = event_data->u.frame_msg.timestamp; - int main_id = event_data->u.frame_msg.frame_id; - int real_id = event_data->u.frame_msg.request_id; - - if (real_id != 0) { // next ready - if (real_id == 1) {s->idx_offset = main_id;} - int buf_idx = (real_id - 1) % FRAME_BUF_COUNT; - - // check for skipped frames - if (main_id > s->frame_id_last + 1 && !s->skipped) { - // realign - clear_req_queue(s->multi_cam_state->video0_fd, event_data->session_hdl, event_data->u.frame_msg.link_hdl); - enqueue_req_multi(s, real_id + 1, FRAME_BUF_COUNT - 1, 0); - s->skipped = true; - } else if (main_id == s->frame_id_last + 1) { - s->skipped = false; - } - - // check for dropped requests - if (real_id > s->request_id_last + 1) { - enqueue_req_multi(s, s->request_id_last + 1 + FRAME_BUF_COUNT, real_id - (s->request_id_last + 1), 0); - } - - // metas - s->frame_id_last = main_id; - s->request_id_last = real_id; - - auto &meta_data = s->buf.camera_bufs_metadata[buf_idx]; - meta_data.frame_id = main_id - s->idx_offset; - meta_data.timestamp_sof = timestamp; - s->exp_lock.lock(); - meta_data.global_gain = s->analog_gain + (100*s->dc_gain_enabled); - meta_data.gain_frac = s->analog_gain_frac; - meta_data.integ_lines = s->exposure_time; - s->exp_lock.unlock(); - - // dispatch - enqueue_req_multi(s, real_id + FRAME_BUF_COUNT, 1, 1); - } else { // not ready - // reset after half second of no response - if (main_id > s->frame_id_last + 10) { - clear_req_queue(s->multi_cam_state->video0_fd, event_data->session_hdl, event_data->u.frame_msg.link_hdl); - enqueue_req_multi(s, s->request_id_last + 1, FRAME_BUF_COUNT, 0); - s->frame_id_last = main_id; - s->skipped = true; - } - } -} - -// ******************* exposure control helpers ******************* - -void set_exposure_time_bounds(CameraState *s) { - switch (s->analog_gain) { - case 0: { - s->exposure_time_min = EXPOSURE_TIME_MIN; - s->exposure_time_max = EXPOSURE_TIME_MAX; // EXPOSURE_TIME_MIN * 4; - break; - } - case ANALOG_GAIN_MAX_IDX - 1: { - s->exposure_time_min = EXPOSURE_TIME_MIN; // EXPOSURE_TIME_MAX / 4; - s->exposure_time_max = EXPOSURE_TIME_MAX; - break; - } - default: { - // finetune margins on both ends - float k_up = sensor_analog_gains[s->analog_gain+1] / sensor_analog_gains[s->analog_gain]; - float k_down = sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain]; - s->exposure_time_min = k_down * EXPOSURE_TIME_MIN * 2; - s->exposure_time_max = k_up * EXPOSURE_TIME_MAX / 2; - } - } -} - -void switch_conversion_gain(CameraState *s) { - if (!s->dc_gain_enabled) { - s->dc_gain_enabled = true; - s->analog_gain -= 4; - } else { - s->dc_gain_enabled = false; - s->analog_gain += 4; - } -} - -static void set_camera_exposure(CameraState *s, float grey_frac) { - // TODO: get stats from sensor? - float target_grey = 0.4 - ((float)(s->analog_gain + 4*s->dc_gain_enabled) / 48.0f); - float exposure_factor = 1 + 30 * pow((target_grey - grey_frac), 3); - exposure_factor = std::max(exposure_factor, 0.56f); - - if (s->camera_num != 1) { - s->ef_filtered = (1 - EF_LOWPASS_K) * s->ef_filtered + EF_LOWPASS_K * exposure_factor; - exposure_factor = s->ef_filtered; - } - - s->exp_lock.lock(); - // always prioritize exposure time adjust - s->exposure_time *= exposure_factor; - - // switch gain if max/min exposure time is reached - // or always switch down to a lower gain when possible - bool kd = false; - if (s->analog_gain > 0) { - kd = 1.1 * s->exposure_time / (sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain]) < EXPOSURE_TIME_MAX / 2; - } - - if (s->exposure_time > s->exposure_time_max) { - if (s->analog_gain < ANALOG_GAIN_MAX_IDX - 1) { - s->exposure_time = EXPOSURE_TIME_MAX / 2; - s->analog_gain += 1; - if (!s->dc_gain_enabled && sensor_analog_gains[s->analog_gain] >= 4.0) { // switch to HCG - switch_conversion_gain(s); - } - set_exposure_time_bounds(s); - } else { - s->exposure_time = s->exposure_time_max; - } - } else if (s->exposure_time < s->exposure_time_min || kd) { - if (s->analog_gain > 0) { - s->exposure_time = std::max(EXPOSURE_TIME_MIN * 2, (int)(s->exposure_time / (sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain]))); - s->analog_gain -= 1; - if (s->dc_gain_enabled && sensor_analog_gains[s->analog_gain] <= 1.25) { // switch back to LCG - switch_conversion_gain(s); - } - set_exposure_time_bounds(s); - } else { - s->exposure_time = s->exposure_time_min; - } - } - - // set up config - uint16_t AG = s->analog_gain + 4; - AG = 0xFF00 + AG * 16 + AG; - s->analog_gain_frac = sensor_analog_gains[s->analog_gain]; - - s->exp_lock.unlock(); - // printf("cam %d, min %d, max %d \n", s->camera_num, s->exposure_time_min, s->exposure_time_max); - // printf("cam %d, set AG to 0x%X, S to %d, dc %d \n", s->camera_num, AG, s->exposure_time, s->dc_gain_enabled); - - struct i2c_random_wr_payload exp_reg_array[] = { - {0x3366, AG}, // analog gain - {0x3362, (uint16_t)(s->dc_gain_enabled?0x1:0x0)}, // DC_GAIN - {0x305A, 0x00F8}, // red gain - {0x3058, 0x0122}, // blue gain - {0x3056, 0x009A}, // g1 gain - {0x305C, 0x009A}, // g2 gain - {0x3012, (uint16_t)s->exposure_time}, // integ time - }; - //{0x301A, 0x091C}}; // reset - sensors_i2c(s, exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), - CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); -} - -void camera_autoexposure(CameraState *s, float grey_frac) { - CameraExpInfo tmp = cam_exp[s->camera_num].load(); - tmp.op_id++; - tmp.grey_frac = grey_frac; - cam_exp[s->camera_num].store(tmp); -} - -static void ae_thread(MultiCameraState *s) { - CameraState *c_handles[3] = {&s->wide_road_cam, &s->road_cam, &s->driver_cam}; - - int op_id_last[3] = {0}; - CameraExpInfo cam_op[3]; - - set_thread_name("camera_settings"); - - while(!do_exit) { - for (int i=0;i<3;i++) { - cam_op[i] = cam_exp[i].load(); - if (cam_op[i].op_id != op_id_last[i]) { - set_camera_exposure(c_handles[i], cam_op[i].grey_frac); - op_id_last[i] = cam_op[i].op_id; - } - } - - util::sleep_for(50); - } -} - -void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { - common_process_driver_camera(s->sm, s->pm, c, cnt); -} - -// called by processing_thread -void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { - const CameraBuf *b = &c->buf; - - MessageBuilder msg; - auto framed = c == &s->road_cam ? msg.initEvent().initRoadCameraState() : msg.initEvent().initWideRoadCameraState(); - fill_frame_data(framed, b->cur_frame_data); - if ((c == &s->road_cam && env_send_road) || (c == &s->wide_road_cam && env_send_wide_road)) { - framed.setImage(get_frame_image(b)); - } - if (c == &s->road_cam) { - framed.setTransform(b->yuv_transform.v); - } - s->pm->send(c == &s->road_cam ? "roadCameraState" : "wideRoadCameraState", msg); - - if (cnt % 3 == 0) { - const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); - const int skip = 2; - camera_autoexposure(c, set_exposure_target(b, x, x + w, skip, y, y + h, skip, (int)c->analog_gain, true, true)); - } -} - -void cameras_run(MultiCameraState *s) { - LOG("-- Starting threads"); - std::vector threads; - threads.push_back(std::thread(ae_thread, s)); - threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); - threads.push_back(start_process_thread(s, &s->driver_cam, process_driver_camera)); - threads.push_back(start_process_thread(s, &s->wide_road_cam, process_road_camera)); - - // start devices - LOG("-- Starting devices"); - int start_reg_len = sizeof(start_reg_array) / sizeof(struct i2c_random_wr_payload); - sensors_i2c(&s->road_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); - sensors_i2c(&s->wide_road_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); - sensors_i2c(&s->driver_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); - - // poll events - LOG("-- Dequeueing Video events"); - while (!do_exit) { - struct pollfd fds[1] = {{0}}; - - fds[0].fd = s->video0_fd; - fds[0].events = POLLPRI; - - int ret = poll(fds, std::size(fds), 1000); - if (ret < 0) { - if (errno == EINTR || errno == EAGAIN) continue; - LOGE("poll failed (%d - %d)", ret, errno); - break; - } - - if (!fds[0].revents) continue; - - struct v4l2_event ev = {0}; - ret = ioctl(fds[0].fd, VIDIOC_DQEVENT, &ev); - if (ev.type == 0x8000000) { - struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)ev.u.data; - // LOGD("v4l2 event: sess_hdl %d, link_hdl %d, frame_id %d, req_id %lld, timestamp 0x%llx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status); - // printf("sess_hdl %d, link_hdl %d, frame_id %lu, req_id %lu, timestamp 0x%lx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status); - - if (event_data->session_hdl == s->road_cam.req_mgr_session_info.session_hdl) { - handle_camera_event(&s->road_cam, event_data); - } else if (event_data->session_hdl == s->wide_road_cam.req_mgr_session_info.session_hdl) { - handle_camera_event(&s->wide_road_cam, event_data); - } else if (event_data->session_hdl == s->driver_cam.req_mgr_session_info.session_hdl) { - handle_camera_event(&s->driver_cam, event_data); - } else { - printf("Unknown vidioc event source\n"); - assert(false); - } - } - } - - LOG(" ************** STOPPING **************"); - - for (auto &t : threads) t.join(); - - cameras_close(s); -} diff --git a/selfdrive/camerad/cameras/camera_qcom2.h b/selfdrive/camerad/cameras/camera_qcom2.h deleted file mode 100644 index 851dab9f4..000000000 --- a/selfdrive/camerad/cameras/camera_qcom2.h +++ /dev/null @@ -1,79 +0,0 @@ -#pragma once - -#include -#include - -#include - -#include "selfdrive/camerad/cameras/camera_common.h" -#include "selfdrive/common/util.h" - -#define FRAME_BUF_COUNT 4 - -#define ANALOG_GAIN_MAX_IDX 10 // 0xF is bypass -#define EXPOSURE_TIME_MIN 2 // with HDR, fastest ss -#define EXPOSURE_TIME_MAX 1904 // with HDR, slowest ss - -#define EF_LOWPASS_K 0.35 - -#define DEBAYER_LOCAL_WORKSIZE 16 - -typedef struct CameraState { - MultiCameraState *multi_cam_state; - CameraInfo ci; - - std::mutex exp_lock; - float analog_gain_frac; - uint16_t analog_gain; - bool dc_gain_enabled; - int exposure_time; - int exposure_time_min; - int exposure_time_max; - float ef_filtered; - - unique_fd sensor_fd; - unique_fd csiphy_fd; - - int camera_num; - - uint32_t session_handle; - - uint32_t sensor_dev_handle; - uint32_t isp_dev_handle; - uint32_t csiphy_dev_handle; - - int32_t link_handle; - - int buf0_handle; - int buf_handle[FRAME_BUF_COUNT]; - int sync_objs[FRAME_BUF_COUNT]; - int request_ids[FRAME_BUF_COUNT]; - int request_id_last; - int frame_id_last; - int idx_offset; - bool skipped; - - struct cam_req_mgr_session_info req_mgr_session_info; - - CameraBuf buf; -} CameraState; - -typedef struct MultiCameraState { - int device; - - unique_fd video0_fd; - unique_fd video1_fd; - unique_fd isp_fd; - int device_iommu; - int cdm_iommu; - - - CameraState road_cam; - CameraState wide_road_cam; - CameraState driver_cam; - - pthread_mutex_t isp_lock; - - SubMaster *sm; - PubMaster *pm; -} MultiCameraState; diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/selfdrive/camerad/cameras/sensor2_i2c.h index 5898bd4cc..38a05820f 100644 --- a/selfdrive/camerad/cameras/sensor2_i2c.h +++ b/selfdrive/camerad/cameras/sensor2_i2c.h @@ -56,7 +56,10 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x337A, 0x0C80}, // DBLC_SCALE0 {0x3370, 0x03B1}, // DBLC {0x3044, 0x0400}, // DARK_CONTROL - {0x31E0, 0x0001}, // PDC + + // Enable dead pixel correction using + // the 1D line correction scheme + {0x31E0, 0x0003}, // HDR Settings {0x3082, 0x0004}, // OPERATION_MODE_CTRL diff --git a/selfdrive/camerad/imgproc/utils.cc b/selfdrive/camerad/imgproc/utils.cc index 5c2110131..ad6452c6a 100644 --- a/selfdrive/camerad/imgproc/utils.cc +++ b/selfdrive/camerad/imgproc/utils.cc @@ -1,11 +1,10 @@ #include "selfdrive/camerad/imgproc/utils.h" -#include -#include -#include - #include +#include +#include #include +#include const int16_t lapl_conv_krnl[9] = {0, 1, 0, 1, -4, 1, diff --git a/selfdrive/camerad/imgproc/utils.h b/selfdrive/camerad/imgproc/utils.h index d7d518c0f..72baa5d53 100644 --- a/selfdrive/camerad/imgproc/utils.h +++ b/selfdrive/camerad/imgproc/utils.h @@ -1,8 +1,7 @@ #pragma once -#include -#include - +#include +#include #include #include "selfdrive/common/clutil.h" diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 9636fd27b..b4cf162d2 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -1,9 +1,9 @@ -#include #include -#include #include #include +#include +#include #include #include "libyuv.h" diff --git a/selfdrive/camerad/transforms/rgb_to_yuv.cc b/selfdrive/camerad/transforms/rgb_to_yuv.cc index 1fdeb593d..63e032e2d 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv.cc +++ b/selfdrive/camerad/transforms/rgb_to_yuv.cc @@ -1,6 +1,7 @@ -#include "rgb_to_yuv.h" +#include "selfdrive/camerad/transforms/rgb_to_yuv.h" -#include +#include +#include Rgb2Yuv::Rgb2Yuv(cl_context ctx, cl_device_id device_id, int width, int height, int rgb_stride) { assert(width % 2 == 0 && height % 2 == 0); diff --git a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc b/selfdrive/camerad/transforms/rgb_to_yuv_test.cc index 04b6afd09..74db2bc1c 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv_test.cc +++ b/selfdrive/camerad/transforms/rgb_to_yuv_test.cc @@ -1,11 +1,11 @@ #include #include -#include #include -#include #include #include +#include +#include #include #include #include @@ -145,8 +145,8 @@ int main(int argc, char** argv) { int counter = 0; srand (time(NULL)); - for (int i = 0; i < 100; i++){ - for (int i = 0; i < width * height * 3; i++){ + for (int i = 0; i < 100; i++) { + for (int i = 0; i < width * height * 3; i++) { rgb_frame[i] = (uint8_t)rand(); } diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index ba214410d..c0c4f4bf0 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -170,7 +170,8 @@ def fingerprint(logcan, sendcan): car_fingerprint = fixed_fingerprint source = car.CarParams.FingerprintSource.fixed - cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, source=source, fuzzy=not exact_match) + cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, + source=source, fuzzy=not exact_match, fw_count=len(car_fw)) return car_fingerprint, finger, vin, car_fw, source, exact_match diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index 63d1fbe0b..c72f15529 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -8,7 +8,7 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert def create_lkas_hud(packer, gear, lkas_active, hud_alert, hud_count, lkas_car_model): # LKAS_HUD 0x2a6 (678) Controls what lane-keeping icon is displayed. - if hud_alert == VisualAlert.steerRequired: + if hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw]: msg = b'\x00\x00\x00\x03\x00\x00\x00\x00' return make_can_msg(0x2a6, msg, 0) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index f37ae953a..263e31706 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -49,8 +49,6 @@ class CarInterface(CarInterfaceBase): # 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.enableCamera = True - ret.enableBsm = 720 in fingerprint[0] return ret diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 8f842083e..04fd9ec08 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -20,7 +20,7 @@ class CAR: JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk -# Unique can messages: +# Unique CAN messages: # Only the hybrids have 270: 8 # Only the gas have 55: 8, 416: 7 # For 564, All 2017 have length 4, whereas 2018-19 have length 8. @@ -32,46 +32,52 @@ class CAR: # For 924, Trailhawk 2017 has length 3, whereas 2018 V6 has length 8. FINGERPRINTS = { - CAR.PACIFICA_2017_HYBRID: [ - {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 788:3, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8}, - ], - CAR.PACIFICA_2018: [ - {55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8}, - {55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8}, - ], - CAR.PACIFICA_2020: [{ - 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 536: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 776: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1543: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2016: 8, 2017:8, 2024: 8, 2025: 8 + CAR.PACIFICA_2017_HYBRID: [{ + 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 788:3, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8 }], - CAR.PACIFICA_2018_HYBRID: [ - {68: 8, 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8}, + CAR.PACIFICA_2018: [{ + 55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8 + }, + { + 55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8 + }], + CAR.PACIFICA_2020: [{ + 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 536: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 776: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 886: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1543: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 2015: 8, 2016: 8, 2017:8, 2024: 8, 2025: 8 + }], + CAR.PACIFICA_2018_HYBRID: [{ + 68: 8, 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8 + }, # based on 9ae7821dc4e92455|2019-07-01--16-42-55 - {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2016: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8}, - ], - CAR.PACIFICA_2019_HYBRID: [ - {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8}, + { + 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2016: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8 + }], + CAR.PACIFICA_2019_HYBRID: [{ + 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8 + }, # Based on 0607d2516fc2148f|2019-02-13--23-03-16 - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1537: 8 - }, + { + 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1537: 8 + }, # Based on 3c7ce223e3571b54|2019-05-11--20-16-14 - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1562: 8, 1570: 8 - }, + { + 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1562: 8, 1570: 8 + }, # Based on "8190c7275a24557b|2020-02-24--09-57-23" - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 650: 8, 653: 8, 654: 8, 655: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 683: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 796: 8, 797: 8, 798: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 805: 8, 807: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 886: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2015: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8 - } - ], - CAR.JEEP_CHEROKEE: [ + { + 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 650: 8, 653: 8, 654: 8, 655: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 683: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 796: 8, 797: 8, 798: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 805: 8, 807: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 886: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2015: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8 + }], + CAR.JEEP_CHEROKEE: [{ # JEEP GRAND CHEROKEE V6 2018 - {55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, + 55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8 + }, # Jeep Grand Cherokee 2017 Trailhawk - {257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 658: 6, 660: 8, 671: 8, 672: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, + { + 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 658: 6, 660: 8, 671: 8, 672: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, ], - CAR.JEEP_CHEROKEE_2019: [ + CAR.JEEP_CHEROKEE_2019: [{ # Jeep Grand Cherokee 2019, including most 2020 models - {55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8}, - ], + 55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], } diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index 0949ffe22..06c5f2579 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -4,6 +4,7 @@ from selfdrive.car import make_can_msg from selfdrive.car.ford.fordcan import create_steer_command, create_lkas_ui, spam_cancel_button from opendbc.can.packer import CANPacker +VisualAlert = car.CarControl.HUDControl.VisualAlert MAX_STEER_DELTA = 1 TOGGLE_DEBUG = False @@ -11,7 +12,6 @@ TOGGLE_DEBUG = False class CarController(): def __init__(self, dbc_name, CP, VM): self.packer = CANPacker(dbc_name) - self.enable_camera = CP.enableCamera self.enabled_last = False self.main_on_last = False self.vehicle_model = VM @@ -22,67 +22,65 @@ class CarController(): def update(self, enabled, CS, frame, actuators, visual_alert, pcm_cancel): can_sends = [] - steer_alert = visual_alert == car.CarControl.HUDControl.VisualAlert.steerRequired + steer_alert = visual_alert in [VisualAlert.steerRequired, VisualAlert.ldw] apply_steer = actuators.steer - if self.enable_camera: + if pcm_cancel: + #print "CANCELING!!!!" + can_sends.append(spam_cancel_button(self.packer)) - if pcm_cancel: - #print "CANCELING!!!!" - can_sends.append(spam_cancel_button(self.packer)) + if (frame % 3) == 0: - if (frame % 3) == 0: + curvature = self.vehicle_model.calc_curvature(actuators.steeringAngleDeg*math.pi/180., CS.out.vEgo) - curvature = self.vehicle_model.calc_curvature(actuators.steeringAngleDeg*math.pi/180., CS.out.vEgo) + # The use of the toggle below is handy for trying out the various LKAS modes + if TOGGLE_DEBUG: + self.lkas_action += int(CS.out.genericToggle and not self.generic_toggle_last) + self.lkas_action &= 0xf + else: + self.lkas_action = 5 # 4 and 5 seem the best. 8 and 9 seem to aggressive and laggy - # The use of the toggle below is handy for trying out the various LKAS modes - if TOGGLE_DEBUG: - self.lkas_action += int(CS.out.genericToggle and not self.generic_toggle_last) - self.lkas_action &= 0xf - else: - self.lkas_action = 5 # 4 and 5 seem the best. 8 and 9 seem to aggressive and laggy + can_sends.append(create_steer_command(self.packer, apply_steer, enabled, + CS.lkas_state, CS.out.steeringAngleDeg, curvature, self.lkas_action)) + self.generic_toggle_last = CS.out.genericToggle - can_sends.append(create_steer_command(self.packer, apply_steer, enabled, - CS.lkas_state, CS.out.steeringAngleDeg, curvature, self.lkas_action)) - self.generic_toggle_last = CS.out.genericToggle + if (frame % 100) == 0: - if (frame % 100) == 0: + can_sends.append(make_can_msg(973, b'\x00\x00\x00\x00\x00\x00\x00\x00', 0)) + #can_sends.append(make_can_msg(984, b'\x00\x00\x00\x00\x80\x45\x60\x30', 0)) - can_sends.append(make_can_msg(973, b'\x00\x00\x00\x00\x00\x00\x00\x00', 0)) - #can_sends.append(make_can_msg(984, b'\x00\x00\x00\x00\x80\x45\x60\x30', 0)) + if (frame % 100) == 0 or (self.enabled_last != enabled) or (self.main_on_last != CS.out.cruiseState.available) or \ + (self.steer_alert_last != steer_alert): + can_sends.append(create_lkas_ui(self.packer, CS.out.cruiseState.available, enabled, steer_alert)) - if (frame % 100) == 0 or (self.enabled_last != enabled) or (self.main_on_last != CS.out.cruiseState.available) or \ - (self.steer_alert_last != steer_alert): - can_sends.append(create_lkas_ui(self.packer, CS.out.cruiseState.available, enabled, steer_alert)) + if (frame % 200) == 0: + can_sends.append(make_can_msg(1875, b'\x80\xb0\x55\x55\x78\x90\x00\x00', 1)) - if (frame % 200) == 0: - can_sends.append(make_can_msg(1875, b'\x80\xb0\x55\x55\x78\x90\x00\x00', 1)) + if (frame % 10) == 0: - if (frame % 10) == 0: + can_sends.append(make_can_msg(1648, b'\x00\x00\x00\x40\x00\x00\x50\x00', 1)) + can_sends.append(make_can_msg(1649, b'\x10\x10\xf1\x70\x04\x00\x00\x00', 1)) - can_sends.append(make_can_msg(1648, b'\x00\x00\x00\x40\x00\x00\x50\x00', 1)) - can_sends.append(make_can_msg(1649, b'\x10\x10\xf1\x70\x04\x00\x00\x00', 1)) + can_sends.append(make_can_msg(1664, b'\x00\x00\x03\xe8\x00\x01\xa9\xb2', 1)) + can_sends.append(make_can_msg(1674, b'\x08\x00\x00\xff\x0c\xfb\x6a\x08', 1)) + can_sends.append(make_can_msg(1675, b'\x00\x00\x3b\x60\x37\x00\x00\x00', 1)) + can_sends.append(make_can_msg(1690, b'\x70\x00\x00\x55\x86\x1c\xe0\x00', 1)) - can_sends.append(make_can_msg(1664, b'\x00\x00\x03\xe8\x00\x01\xa9\xb2', 1)) - can_sends.append(make_can_msg(1674, b'\x08\x00\x00\xff\x0c\xfb\x6a\x08', 1)) - can_sends.append(make_can_msg(1675, b'\x00\x00\x3b\x60\x37\x00\x00\x00', 1)) - can_sends.append(make_can_msg(1690, b'\x70\x00\x00\x55\x86\x1c\xe0\x00', 1)) + can_sends.append(make_can_msg(1910, b'\x06\x4b\x06\x4b\x42\xd3\x11\x30', 1)) + can_sends.append(make_can_msg(1911, b'\x48\x53\x37\x54\x48\x53\x37\x54', 1)) + can_sends.append(make_can_msg(1912, b'\x31\x34\x47\x30\x38\x31\x43\x42', 1)) + can_sends.append(make_can_msg(1913, b'\x31\x34\x47\x30\x38\x32\x43\x42', 1)) + can_sends.append(make_can_msg(1969, b'\xf4\x40\x00\x00\x00\x00\x00\x00', 1)) + can_sends.append(make_can_msg(1971, b'\x0b\xc0\x00\x00\x00\x00\x00\x00', 1)) - can_sends.append(make_can_msg(1910, b'\x06\x4b\x06\x4b\x42\xd3\x11\x30', 1)) - can_sends.append(make_can_msg(1911, b'\x48\x53\x37\x54\x48\x53\x37\x54', 1)) - can_sends.append(make_can_msg(1912, b'\x31\x34\x47\x30\x38\x31\x43\x42', 1)) - can_sends.append(make_can_msg(1913, b'\x31\x34\x47\x30\x38\x32\x43\x42', 1)) - can_sends.append(make_can_msg(1969, b'\xf4\x40\x00\x00\x00\x00\x00\x00', 1)) - can_sends.append(make_can_msg(1971, b'\x0b\xc0\x00\x00\x00\x00\x00\x00', 1)) + static_msgs = range(1653, 1658) + for addr in static_msgs: + cnt = (frame % 10) + 1 + can_sends.append(make_can_msg(addr, (cnt << 4).to_bytes(1, 'little') + b'\x00\x00\x00\x00\x00\x00\x00', 1)) - static_msgs = range(1653, 1658) - for addr in static_msgs: - cnt = (frame % 10) + 1 - can_sends.append(make_can_msg(addr, (cnt << 4).to_bytes(1, 'little') + b'\x00\x00\x00\x00\x00\x00\x00', 1)) - - self.enabled_last = enabled - self.main_on_last = CS.out.cruiseState.available - self.steer_alert_last = steer_alert + self.enabled_last = enabled + self.main_on_last = CS.out.cruiseState.available + self.steer_alert_last = steer_alert return can_sends diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index aec368cd0..f5923515e 100755 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 from cereal import car -from selfdrive.swaglog import cloudlog from selfdrive.config import Conversions as CV from selfdrive.car.ford.values import MAX_ANGLE from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint @@ -43,9 +42,6 @@ class CarInterface(CarInterfaceBase): ret.steerControlType = car.CarParams.SteerControlType.angle - ret.enableCamera = True - cloudlog.warning("ECU Camera Simulated: %r", ret.enableCamera) - return ret # returns a car.CarState diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 116a562ac..71490b1cb 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -100,7 +100,7 @@ class CarController(): lka_critical = lka_active and abs(actuators.steer) > 0.9 lka_icon_status = (lka_active, lka_critical) if frame % P.CAMERA_KEEPALIVE_STEP == 0 or lka_icon_status != self.lka_icon_status_last: - steer_alert = hud_alert == VisualAlert.steerRequired + steer_alert = hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw] can_sends.append(gmcan.create_lka_icon_command(CanBus.SW_GMLAN, lka_active, lka_critical, steer_alert)) self.lka_icon_status_last = lka_icon_status diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 7c28406cb..85578cd98 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -20,7 +20,7 @@ class CarInterface(CarInterfaceBase): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "gm" ret.safetyModel = car.CarParams.SafetyModel.gm - ret.enableCruise = False # stock cruise control is kept off + ret.pcmCruise = False # stock cruise control is kept off # GM port is a community feature # TODO: make a port that uses a car harness and it only intercepts the camera @@ -29,8 +29,7 @@ class CarInterface(CarInterfaceBase): # Presence of a camera on the object bus is ok. # Have to go to read_only if ASCM is online (ACC-enabled cars), # or camera is on powertrain bus (LKA cars without ACC). - ret.enableCamera = True - ret.openpilotLongitudinalControl = ret.enableCamera + ret.openpilotLongitudinalControl = True tire_stiffness_factor = 0.444 # not optimized yet # Start with a baseline lateral tuning for all GM vehicles. Override tuning as needed in each model section below. @@ -106,7 +105,6 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [0.36] - ret.stoppingControl = True ret.startAccel = 0.8 ret.steerLimitTimer = 0.4 diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 9f8d9fa75..6f6b0d722 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -89,6 +89,10 @@ FINGERPRINTS = { 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8, }], CAR.ACADIA: [ + # Acadia Denali w/ACC 2018 + { + 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 + }, # Acadia Denali w/ /ACC 2018 { 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 53304583b..3f43fc581 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -10,6 +10,7 @@ from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert + def actuator_hystereses(brake, braking, brake_steady, v_ego, car_fingerprint): # hyst params brake_hyst_on = 0.02 # to activate brakes exceed this value @@ -62,7 +63,7 @@ def process_hud_alert(hud_alert): # priority is: FCW, steer required, all others if hud_alert == VisualAlert.fcw: fcw_display = VISUAL_HUD[hud_alert.raw] - elif hud_alert == VisualAlert.steerRequired: + elif hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw]: steer_required = VISUAL_HUD[hud_alert.raw] else: acc_alert = VISUAL_HUD[hud_alert.raw] @@ -103,7 +104,7 @@ class CarController(): # Never send cancel command if we never enter cruise state (no cruise if pedal) # Cancel cmd causes brakes to release at a standstill causing grinding - pcm_cancel_cmd = pcm_cancel_cmd and CS.CP.enableCruise + pcm_cancel_cmd = pcm_cancel_cmd and CS.CP.pcmCruise # *** rate limit after the enable check *** self.brake_last = rate_limit(brake, self.brake_last, -2., DT_CTRL) @@ -137,6 +138,11 @@ class CarController(): # Send CAN commands. can_sends = [] + # tester present - w/ no response (keeps radar disabled) + if CS.CP.carFingerprint in HONDA_BOSCH and CS.CP.openpilotLongitudinalControl: + if (frame % 10) == 0: + can_sends.append((0x18DAB0F1, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", 1)) + # Send steering command. idx = frame % 4 can_sends.append(hondacan.create_steering_control(self.packer, apply_steer, @@ -163,7 +169,19 @@ class CarController(): idx = frame // 2 ts = frame * DT_CTRL if CS.CP.carFingerprint in HONDA_BOSCH: - pass # TODO: implement + accel = actuators.gas - actuators.brake + + # TODO: pass in LoC.long_control_state and use that to decide starting/stoppping + stopping = accel < 0 and CS.out.vEgo < 0.3 + starting = accel > 0 and CS.out.vEgo < 0.3 + + # Prevent rolling backwards + accel = -1.0 if stopping else accel + + apply_accel = interp(accel, P.BOSCH_ACCEL_LOOKUP_BP, P.BOSCH_ACCEL_LOOKUP_V) + apply_gas = interp(accel, P.BOSCH_GAS_LOOKUP_BP, P.BOSCH_GAS_LOOKUP_V) + can_sends.extend(hondacan.create_acc_commands(self.packer, enabled, apply_accel, apply_gas, idx, stopping, starting, CS.CP.carFingerprint)) + else: apply_gas = clip(actuators.gas, 0., 1.) apply_brake = int(clip(self.brake_last * P.BRAKE_MAX, 0, P.BRAKE_MAX - 1)) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index d081fef0d..3067c5e29 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -92,29 +92,27 @@ def get_can_signals(CP, gearbox_msg="GEARBOX"): signals += [ ("CAR_GAS", "GAS_PEDAL_2", 0), ("MAIN_ON", "SCM_FEEDBACK", 0), - ("CRUISE_CONTROL_LABEL", "ACC_HUD", 0), ("EPB_STATE", "EPB_STATUS", 0), - ("CRUISE_SPEED", "ACC_HUD", 0), - ("ACCEL_COMMAND", "ACC_CONTROL", 0), - ("AEB_STATUS", "ACC_CONTROL", 0), ] checks += [ - ("ACC_HUD", 10), ("EPB_STATUS", 50), ("GAS_PEDAL_2", 100), - ("ACC_CONTROL", 50), ] - if CP.openpilotLongitudinalControl: - signals += [("BRAKE_ERROR_1", "STANDSTILL", 1), - ("BRAKE_ERROR_2", "STANDSTILL", 1)] - checks += [("STANDSTILL", 50)] - else: - # Nidec signals. - signals += [("BRAKE_ERROR_1", "STANDSTILL", 1), - ("BRAKE_ERROR_2", "STANDSTILL", 1), - ("CRUISE_SPEED_PCM", "CRUISE", 0), + + if not CP.openpilotLongitudinalControl: + signals += [ + ("CRUISE_CONTROL_LABEL", "ACC_HUD", 0), + ("CRUISE_SPEED", "ACC_HUD", 0), + ("ACCEL_COMMAND", "ACC_CONTROL", 0), + ("AEB_STATUS", "ACC_CONTROL", 0), + ] + checks += [ + ("ACC_HUD", 10), + ("ACC_CONTROL", 50), + ] + else: # Nidec signals + signals += [("CRUISE_SPEED_PCM", "CRUISE", 0), ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS", 0)] - checks += [("STANDSTILL", 50)] if CP.carFingerprint == CAR.ODYSSEY_CHN: checks += [("CRUISE_PARAMS", 10)] @@ -192,6 +190,13 @@ def get_can_signals(CP, gearbox_msg="GEARBOX"): signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR", 0)) checks.append(("GAS_SENSOR", 50)) + if CP.openpilotLongitudinalControl: + signals += [ + ("BRAKE_ERROR_1", "STANDSTILL", 1), + ("BRAKE_ERROR_2", "STANDSTILL", 1) + ] + checks += [("STANDSTILL", 50)] + return signals, checks @@ -211,7 +216,6 @@ class CarState(CarStateBase): self.brake_switch_prev_ts = 0 self.cruise_setting = 0 self.v_cruise_pcm_prev = 0 - self.cruise_mode = 0 def update(self, cp, cp_cam, cp_body): ret = car.CarState.new_message() @@ -271,8 +275,8 @@ class CarState(CarStateBase): self.cruise_setting = cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] self.cruise_buttons = cp.vl["SCM_BUTTONS"]["CRUISE_BUTTONS"] - ret.leftBlinker = cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"] != 0 - ret.rightBlinker = cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"] != 0 + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk( + 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) self.brake_hold = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, @@ -310,12 +314,13 @@ class CarState(CarStateBase): ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD[self.CP.carFingerprint] if self.CP.carFingerprint in HONDA_BOSCH: - self.cruise_mode = cp.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] - ret.cruiseState.standstill = cp.vl["ACC_HUD"]["CRUISE_SPEED"] == 252. - ret.cruiseState.speedOffset = calc_cruise_offset(0, ret.vEgo) - # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. - ret.cruiseState.speed = self.v_cruise_pcm_prev if cp.vl["ACC_HUD"]["CRUISE_SPEED"] > 160.0 else cp.vl["ACC_HUD"]["CRUISE_SPEED"] * CV.KPH_TO_MS - self.v_cruise_pcm_prev = ret.cruiseState.speed + if not self.CP.openpilotLongitudinalControl: + ret.cruiseState.nonAdaptive = cp.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] != 0 + ret.cruiseState.standstill = cp.vl["ACC_HUD"]["CRUISE_SPEED"] == 252. + + # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. + ret.cruiseState.speed = self.v_cruise_pcm_prev if cp.vl["ACC_HUD"]["CRUISE_SPEED"] > 160.0 else cp.vl["ACC_HUD"]["CRUISE_SPEED"] * CV.KPH_TO_MS + self.v_cruise_pcm_prev = ret.cruiseState.speed else: ret.cruiseState.speedOffset = calc_cruise_offset(cp.vl["CRUISE_PARAMS"]["CRUISE_SPEED_OFFSET"], ret.vEgo) ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS @@ -336,7 +341,6 @@ class CarState(CarStateBase): ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"] ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 ret.cruiseState.available = bool(main_on) - ret.cruiseState.nonAdaptive = self.cruise_mode != 0 # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models if self.CP.carFingerprint in (CAR.PILOT, CAR.PILOT_2019, CAR.RIDGELINE): @@ -347,7 +351,7 @@ class CarState(CarStateBase): self.is_metric = not cp.vl["HUD_SETTING"]["IMPERIAL_UNIT"] if self.CP.carFingerprint in (CAR.CIVIC) else False if self.CP.carFingerprint in HONDA_BOSCH: - ret.stockAeb = bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) + ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) else: ret.stockAeb = bool(cp_cam.vl["BRAKE_COMMAND"]["AEB_REQ_1"] and cp_cam.vl["BRAKE_COMMAND"]["COMPUTER_BRAKE"] > 1e-5) diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index ef2564702..883d4fe94 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -1,3 +1,5 @@ +from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery +from selfdrive.swaglog import cloudlog from selfdrive.config import Conversions as CV from selfdrive.car.honda.values import HONDA_BOSCH @@ -7,6 +9,13 @@ from selfdrive.car.honda.values import HONDA_BOSCH # 2 = ACC-CAN - camera side # 3 = F-CAN A - OBDII port +RADAR_ADDR = 0x18DAB0F1 +EXT_DIAG_REQUEST = b'\x10\x03' +EXT_DIAG_RESPONSE = b'\x50\x03' +COM_CONT_REQUEST = b'\x28\x83\x03' +COM_CONT_RESPONSE = b'' + + def get_pt_bus(car_fingerprint): return 1 if car_fingerprint in HONDA_BOSCH else 0 @@ -19,6 +28,29 @@ def get_lkas_cmd_bus(car_fingerprint, radar_disabled=False): return 0 +def disable_radar(logcan, sendcan, bus=1, timeout=0.1, debug=False): + """Silence the radar by disabling sending and receiving messages using UDS 0x28. + The radar will stay silent as long as openpilot keeps sending Tester Present. + Openpilot will emulate the radar. WARNING: THIS DISABLES AEB!""" + cloudlog.warning(f"radar disable {hex(RADAR_ADDR)} ...") + + try: + query = IsoTpParallelQuery(sendcan, logcan, bus, [RADAR_ADDR], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) + + for _, _ in query.get_data(timeout).items(): + cloudlog.warning("radar communication control disable tx/rx ...") + + query = IsoTpParallelQuery(sendcan, logcan, bus, [RADAR_ADDR], [COM_CONT_REQUEST], [COM_CONT_RESPONSE], debug=debug) + query.get_data(0) + + cloudlog.warning("radar disabled") + return + + except Exception: + cloudlog.exception("radar disable exception") + cloudlog.warning("radar disable failed") + + def create_brake_command(packer, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, fcw, idx, car_fingerprint, stock_brake): # TODO: do we loose pressure if we keep pump off for long? brakelights = apply_brake > 0 diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 65d61a70d..15446623c 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -1,22 +1,26 @@ #!/usr/bin/env python3 import numpy as np from cereal import car +from panda import Panda from common.numpy_fast import clip, interp -from selfdrive.swaglog import cloudlog +from common.params import Params from selfdrive.config import Conversions as CV -from selfdrive.car.honda.values import CruiseButtons, CAR, HONDA_BOSCH, HONDA_BOSCH_ALT_BRAKE_SIGNAL +from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, CAR, HONDA_BOSCH, HONDA_BOSCH_ALT_BRAKE_SIGNAL +from selfdrive.car.honda.hondacan import disable_radar from selfdrive.car import STD_CARGO_KG, CivicParams, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint -from selfdrive.controls.lib.longitudinal_planner import _A_CRUISE_MAX_V_FOLLOWING from selfdrive.car.interfaces import CarInterfaceBase -A_ACC_MAX = max(_A_CRUISE_MAX_V_FOLLOWING) ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName TransmissionType = car.CarParams.TransmissionType -def compute_gb_honda(accel, speed): +def compute_gb_honda_bosch(accel, speed): + return float(accel) / 3.5 + + +def compute_gb_honda_nidec(accel, speed): creep_brake = 0.0 creep_speed = 2.3 creep_brake_value = 0.15 @@ -76,8 +80,10 @@ class CarInterface(CarInterfaceBase): if self.CS.CP.carFingerprint == CAR.ACURA_ILX: self.compute_gb = get_compute_gb_acura() + elif self.CS.CP.carFingerprint in HONDA_BOSCH: + self.compute_gb = compute_gb_honda_bosch else: - self.compute_gb = compute_gb_honda + self.compute_gb = compute_gb_honda_nidec @staticmethod def compute_gb(accel, speed): # pylint: disable=method-hidden @@ -113,7 +119,7 @@ class CarInterface(CarInterfaceBase): # accelOverride is more or less the max throttle allowed to pcm: usually set to a constant # unless aTargetMax is very high and then we scale with it; this help in quicker restart - return float(max(max_accel, a_target / A_ACC_MAX)) * min(speedLimiter, accelLimiter) + return float(max(max_accel, a_target / CarControllerParams.ACCEL_MAX)) * min(speedLimiter, accelLimiter) @staticmethod def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[]): # pylint: disable=dangerous-default-value @@ -122,14 +128,21 @@ class CarInterface(CarInterfaceBase): if candidate in HONDA_BOSCH: ret.safetyModel = car.CarParams.SafetyModel.hondaBoschHarness - ret.enableCamera = True ret.radarOffCan = True - ret.openpilotLongitudinalControl = False + + # Disable the radar and let openpilot control longitudinal + # WARNING: THIS DISABLES AEB! + ret.openpilotLongitudinalControl = Params().get_bool("DisableRadar") + + ret.pcmCruise = not ret.openpilotLongitudinalControl + ret.communityFeature = ret.openpilotLongitudinalControl else: ret.safetyModel = car.CarParams.SafetyModel.hondaNidec - ret.enableCamera = True ret.enableGasInterceptor = 0x201 in fingerprint[0] - ret.openpilotLongitudinalControl = ret.enableCamera + ret.openpilotLongitudinalControl = True + + ret.pcmCruise = not ret.enableGasInterceptor + ret.communityFeature = ret.enableGasInterceptor if candidate == CAR.CRV_5G: ret.enableBsm = 0x12f8bfa7 in fingerprint[0] @@ -138,12 +151,6 @@ class CarInterface(CarInterfaceBase): if candidate == CAR.ACCORD and 0x191 in fingerprint[1]: ret.transmissionType = TransmissionType.cvt - cloudlog.warning("ECU Camera Simulated: %r", ret.enableCamera) - cloudlog.warning("ECU Gas Interceptor: %r", ret.enableGasInterceptor) - - ret.enableCruise = not ret.enableGasInterceptor - ret.communityFeature = ret.enableGasInterceptor - # Certain Hondas have an extra steering sensor at the bottom of the steering rack, # which improves controls quality as it removes the steering column torsion from feedback. # Tire stiffness factor fictitiously lower if it includes the steering column torsion effect. @@ -408,7 +415,10 @@ class CarInterface(CarInterfaceBase): # These cars use alternate user brake msg (0x1BE) if candidate in HONDA_BOSCH_ALT_BRAKE_SIGNAL: - ret.safetyParam = 1 + ret.safetyParam |= Panda.FLAG_HONDA_ALT_BRAKE + + if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: + ret.safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not @@ -424,12 +434,17 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - ret.gasMaxBP = [0.] # m/s - ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed - ret.brakeMaxBP = [5., 20.] # m/s - ret.brakeMaxV = [1., 0.8] # max brake allowed + if candidate in HONDA_BOSCH: + ret.gasMaxBP = [0.] # m/s + ret.gasMaxV = [0.6] + ret.brakeMaxBP = [0.] # m/s + ret.brakeMaxV = [1.] # max brake allowed, 3.5m/s^2 + else: + ret.gasMaxBP = [0.] # m/s + ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed + ret.brakeMaxBP = [5., 20.] # m/s + ret.brakeMaxV = [1., 0.8] # max brake allowed - ret.stoppingControl = True ret.startAccel = 0.5 ret.steerActuatorDelay = 0.1 @@ -438,6 +453,11 @@ class CarInterface(CarInterfaceBase): return ret + @staticmethod + def init(CP, logcan, sendcan): + if CP.carFingerprint in HONDA_BOSCH and CP.openpilotLongitudinalControl: + disable_radar(logcan, sendcan) + # returns a car.CarState def update(self, c, can_strings): # ******************* do can recv ******************* @@ -488,7 +508,7 @@ class CarInterface(CarInterfaceBase): ret.buttonEvents = buttonEvents # events - events = self.create_common_events(ret, pcm_enable=self.CP.enableCruise) + events = self.create_common_events(ret, pcm_enable=False) if self.CS.brake_error: events.add(EventName.brakeUnavailable) if self.CS.brake_hold and self.CS.CP.openpilotLongitudinalControl: @@ -496,18 +516,21 @@ class CarInterface(CarInterfaceBase): if self.CS.park_brake: events.add(EventName.parkBrake) - if self.CP.enableCruise and ret.vEgo < self.CP.minEnableSpeed: + if self.CP.pcmCruise and ret.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) - # it can happen that car cruise disables while comma system is enabled: need to - # keep braking if needed or if the speed is very low - if self.CP.enableCruise and not ret.cruiseState.enabled \ - and (c.actuators.brake <= 0. or not self.CP.openpilotLongitudinalControl): - # non loud alert if cruise disables below 25mph as expected (+ a little margin) - if ret.vEgo < self.CP.minEnableSpeed + 2.: - events.add(EventName.speedTooLow) - else: - events.add(EventName.cruiseDisabled) + if self.CP.pcmCruise: + # we engage when pcm is active (rising edge) + if ret.cruiseState.enabled and not self.CS.out.cruiseState.enabled: + events.add(EventName.pcmEnable) + elif not ret.cruiseState.enabled and (c.actuators.brake <= 0. or not self.CP.openpilotLongitudinalControl): + # it can happen that car cruise disables while comma system is enabled: need to + # keep braking if needed or if the speed is very low + if ret.vEgo < self.CP.minEnableSpeed + 2.: + # non loud alert if cruise disables below 25mph as expected (+ a little margin) + events.add(EventName.speedTooLow) + else: + events.add(EventName.cruiseDisabled) if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: events.add(EventName.manualRestart) @@ -516,7 +539,7 @@ class CarInterface(CarInterfaceBase): # do enable on both accel and decel buttons if b.type in [ButtonType.accelCruise, ButtonType.decelCruise] and not b.pressed: - if not self.CP.enableCruise: + if not self.CP.pcmCruise: events.add(EventName.buttonEnable) # do disable on button down diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 79bc28d29..289fab9f8 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -7,6 +7,8 @@ Ecu = car.CarParams.Ecu VisualAlert = car.CarControl.HUDControl.VisualAlert class CarControllerParams(): + ACCEL_MAX = 1.6 + def __init__(self, CP): self.BRAKE_MAX = 1024//4 self.STEER_MAX = CP.lateralParams.torqueBP[-1] @@ -16,6 +18,12 @@ class CarControllerParams(): self.STEER_LOOKUP_BP = [v * -1 for v in CP.lateralParams.torqueBP][1:][::-1] + list(CP.lateralParams.torqueBP) self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV) + self.BOSCH_ACCEL_LOOKUP_BP = [-1., 0., 0.6] + self.BOSCH_ACCEL_LOOKUP_V = [-3.5, 0., 2.] + self.BOSCH_GAS_LOOKUP_BP = [0., 0.6] + self.BOSCH_GAS_LOOKUP_V = [0, 2000] + + # Car button codes class CruiseButtons: RES_ACCEL = 4 @@ -28,6 +36,7 @@ VISUAL_HUD = { VisualAlert.none: 0, VisualAlert.fcw: 1, VisualAlert.steerRequired: 1, + VisualAlert.ldw: 1, VisualAlert.brakePressed: 10, VisualAlert.wrongGear: 6, VisualAlert.seatbeltUnbuckled: 5, @@ -59,15 +68,9 @@ class CAR: DIAG_MSGS = {1600: 5, 1601: 8} FINGERPRINTS = { - CAR.ACCORD: [{ - 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8 - }], CAR.ACCORDH: [{ 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 387: 8, 388: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 525: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8 }], - CAR.ACURA_ILX: [{ - 57: 3, 145: 8, 228: 5, 304: 8, 316: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 7, 419: 8, 420: 8, 422: 8, 428: 8, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 882: 2, 884: 7, 887: 8, 888: 8, 892: 8, 923: 2, 929: 4, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1030: 5, 1034: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1365: 5, - }], # Acura RDX w/ Added Comma Pedal Support (512L & 513L) CAR.ACURA_RDX: [{ 57: 3, 145: 8, 229: 4, 308: 5, 316: 8, 342: 6, 344: 8, 380: 8, 392: 6, 398: 3, 399: 6, 404: 4, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 882: 2, 884: 7, 887: 8, 888: 8, 892: 8, 923: 2, 929: 4, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1033: 5, 1034: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1365: 5, 1424: 5, 1729: 1 @@ -86,9 +89,6 @@ FINGERPRINTS = { CAR.CRV_5G: [{ 57: 3, 148: 8, 199: 4, 228: 5, 231: 5, 232: 7, 304: 8, 330: 8, 340: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 423: 2, 427: 3, 428: 8, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 467: 2, 469: 3, 470: 2, 474: 8, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 507: 1, 545: 6, 597: 8, 661: 4, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 814: 4, 815: 8, 817: 4, 825: 4, 829: 5, 862: 8, 881: 8, 882: 4, 884: 8, 888: 8, 891: 8, 927: 8, 918: 7, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1108: 8, 1092: 1, 1115: 2, 1125: 8, 1127: 2, 1296: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1618: 5, 1633: 8, 1670: 5 }], - CAR.FIT: [{ - 57: 3, 145: 8, 228: 5, 304: 8, 342: 6, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 422: 8, 427: 3, 428: 8, 432: 7, 464: 8, 487: 4, 490: 8, 506: 8, 597: 8, 660: 8, 661: 4, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 829: 5, 862: 8, 884: 7, 892: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8 - }], # 2018 Odyssey w/ Added Comma Pedal Support (512L & 513L) CAR.ODYSSEY: [{ 57: 3, 148: 8, 228: 5, 229: 4, 316: 8, 342: 6, 344: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 427: 3, 432: 7, 450: 8, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 862: 8, 871: 8, 881: 8, 882: 4, 884: 8, 891: 8, 892: 8, 905: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1029: 8, 1036: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1302: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1619: 5, 1623: 5, 1668: 5 @@ -100,10 +100,6 @@ FINGERPRINTS = { CAR.ODYSSEY_CHN: [{ 57: 3, 145: 8, 316: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 7, 401: 8, 404: 4, 411: 5, 420: 8, 422: 8, 423: 2, 426: 8, 432: 7, 450: 8, 464: 8, 490: 8, 506: 8, 507: 1, 512: 6, 513: 6, 597: 8, 610: 8, 611: 8, 612: 8, 617: 8, 660: 8, 661: 4, 773: 7, 780: 8, 804: 8, 808: 8, 829: 5, 862: 8, 884: 7, 892: 8, 923: 2, 929: 8, 1030: 5, 1137: 8, 1302: 8, 1348: 5, 1361: 5, 1365: 5, 1600: 5, 1601: 8, 1639: 8 }], - # 2017 Pilot Touring AND 2016 Pilot EX-L w/ Added Comma Pedal Support (512L & 513L) - CAR.PILOT: [{ - 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 334: 8, 339: 7, 342: 6, 344: 8, 379: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 507: 1, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 837: 5, 856: 7, 871: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1618: 5, 1668: 5 - }], # this fingerprint also includes the Passport 2019 CAR.PILOT_2019: [{ 57: 3, 145: 8, 228: 5, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 983: 8, 985: 3, 1029: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 @@ -156,6 +152,7 @@ FW_VERSIONS = { b'28102-6B8-A570\x00\x00', b'28102-6B8-A700\x00\x00', b'28102-6B8-A800\x00\x00', + b'28102-6B8-C560\x00\x00', b'28102-6B8-C570\x00\x00', b'28102-6B8-M520\x00\x00', b'28101-6A7-A220\x00\x00', @@ -624,6 +621,7 @@ FW_VERSIONS = { }, CAR.CRV_5G: { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5PA-AH20\x00\x00', b'37805-5PA-3060\x00\x00', b'37805-5PA-3080\x00\x00', b'37805-5PA-3180\x00\x00', @@ -1138,6 +1136,7 @@ FW_VERSIONS = { b'78109-T6Z-A420\x00\x00', b'78109-T6Z-A510\x00\x00', b'78109-T6Z-A710\x00\x00', + b'78109-T6Z-A910\x00\x00', b'78109-T6Z-AA10\x00\x00', b'78109-T6Z-C620\x00\x00', b'78109-TJZ-A510\x00\x00', diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 5f7019fdf..2bfc40425 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -10,7 +10,7 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert def process_hud_alert(enabled, fingerprint, visual_alert, left_lane, right_lane, left_lane_depart, right_lane_depart): - sys_warning = (visual_alert == VisualAlert.steerRequired) + sys_warning = (visual_alert in [VisualAlert.steerRequired, VisualAlert.ldw]) # initialize to no line visible sys_state = 1 @@ -49,12 +49,8 @@ class CarController(): apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) self.steer_rate_limited = new_steer != apply_steer - # disable when temp fault is active - lkas_active = enabled and not CS.out.steerWarning - - # fix for Genesis hard fault at low speed - if CS.out.vEgo < 16.7 and self.car_fingerprint == CAR.HYUNDAI_GENESIS: - lkas_active = False + # disable when temp fault is active, or below LKA minimum speed + lkas_active = enabled and not CS.out.steerWarning and CS.out.vEgo >= CS.CP.minSteerSpeed if not lkas_active: apply_steer = 0 @@ -82,7 +78,7 @@ class CarController(): # 20 Hz LFA MFA message if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KONA_EV, - CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021]: + CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021]: can_sends.append(create_lfahda_mfc(self.packer, enabled)) return can_sends diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 868838827..2cb176aa1 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -1,14 +1,25 @@ import copy from cereal import car -from selfdrive.car.hyundai.values import DBC, STEER_THRESHOLD, FEATURES, EV_HYBRID +from selfdrive.car.hyundai.values import DBC, STEER_THRESHOLD, FEATURES, EV_CAR, HYBRID_CAR from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser +from opendbc.can.can_define import CANDefine from selfdrive.config import Conversions as CV -GearShifter = car.CarState.GearShifter - class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + if self.CP.carFingerprint in FEATURES["use_cluster_gears"]: + self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] + elif self.CP.carFingerprint in FEATURES["use_tcu_gears"]: + self.shifter_values = can_define.dv["TCU12"]["CUR_GR"] + else: # preferred and elect gear methods use same definition + self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] + + def update(self, cp, cp_cam): ret = car.CarState.new_message() @@ -29,8 +40,8 @@ class CarState(CarStateBase): ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"] ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"] ret.yawRate = cp.vl["ESP12"]["YAW_RATE"] - ret.leftBlinker, ret.rightBlinker = self.update_blinker(50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], - cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp( + 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD @@ -40,7 +51,7 @@ class CarState(CarStateBase): if self.CP.openpilotLongitudinalControl: ret.cruiseState.available = cp.vl["TCS13"]["ACCEnable"] == 0 ret.cruiseState.enabled = cp.vl["TCS13"]["ACC_REQ"] == 1 - ret.cruiseState.standstill = cp.vl["TCS13"]["StandStill"] == 1 + ret.cruiseState.standstill = False else: ret.cruiseState.available = cp.vl["SCC11"]["MainMode_ACC"] == 1 ret.cruiseState.enabled = cp.vl["SCC12"]["ACCMode"] != 0 @@ -56,64 +67,28 @@ class CarState(CarStateBase): ret.brake = 0 ret.brakePressed = cp.vl["TCS13"]["DriverBraking"] != 0 - if self.CP.carFingerprint in EV_HYBRID: - ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 256. + if self.CP.carFingerprint in (HYBRID_CAR | EV_CAR): + if self.CP.carFingerprint in HYBRID_CAR: + ret.gas = cp.vl["E_EMS11"]["CR_Vcu_AccPedDep_Pos"] / 254. + else: + ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 254. ret.gasPressed = ret.gas > 0 else: - ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100 + ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100. ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) - # TODO: refactor gear parsing in function # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, # as this seems to be standard over all cars, but is not the preferred method. if self.CP.carFingerprint in FEATURES["use_cluster_gears"]: - if cp.vl["CLU15"]["CF_Clu_InhibitD"] == 1: - ret.gearShifter = GearShifter.drive - elif cp.vl["CLU15"]["CF_Clu_InhibitN"] == 1: - ret.gearShifter = GearShifter.neutral - elif cp.vl["CLU15"]["CF_Clu_InhibitP"] == 1: - ret.gearShifter = GearShifter.park - elif cp.vl["CLU15"]["CF_Clu_InhibitR"] == 1: - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.unknown - # Gear Selecton via TCU12 + gear = cp.vl["CLU15"]["CF_Clu_Gear"] elif self.CP.carFingerprint in FEATURES["use_tcu_gears"]: gear = cp.vl["TCU12"]["CUR_GR"] - if gear == 0: - ret.gearShifter = GearShifter.park - elif gear == 14: - ret.gearShifter = GearShifter.reverse - elif gear > 0 and gear < 9: # unaware of anything over 8 currently - ret.gearShifter = GearShifter.drive - else: - ret.gearShifter = GearShifter.unknown - # Gear Selecton - This is only compatible with optima hybrid 2017 elif self.CP.carFingerprint in FEATURES["use_elect_gears"]: gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] - if gear in (5, 8): # 5: D, 8: sport mode - ret.gearShifter = GearShifter.drive - elif gear == 6: - ret.gearShifter = GearShifter.neutral - elif gear == 0: - ret.gearShifter = GearShifter.park - elif gear == 7: - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.unknown - # Gear Selecton - This is not compatible with all Kia/Hyundai's, But is the best way for those it is compatible with else: gear = cp.vl["LVR12"]["CF_Lvr_Gear"] - if gear in (5, 8): # 5: D, 8: sport mode - ret.gearShifter = GearShifter.drive - elif gear == 6: - ret.gearShifter = GearShifter.neutral - elif gear == 0: - ret.gearShifter = GearShifter.park - elif gear == 7: - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.unknown + + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) if self.CP.carFingerprint in FEATURES["use_fca"]: ret.stockAeb = cp.vl["FCA11"]["FCA_CmdAct"] != 0 @@ -228,10 +203,15 @@ class CarState(CarStateBase): ] checks += [("LCA11", 50)] - if CP.carFingerprint in EV_HYBRID: - signals += [ - ("Accel_Pedal_Pos", "E_EMS11", 0), - ] + if CP.carFingerprint in (HYBRID_CAR | EV_CAR): + if CP.carFingerprint in HYBRID_CAR: + signals += [ + ("CR_Vcu_AccPedDep_Pos", "E_EMS11", 0) + ] + else: + signals += [ + ("Accel_Pedal_Pos", "E_EMS11", 0) + ] checks += [ ("E_EMS11", 50), ] @@ -247,10 +227,7 @@ class CarState(CarStateBase): if CP.carFingerprint in FEATURES["use_cluster_gears"]: signals += [ - ("CF_Clu_InhibitD", "CLU15", 0), - ("CF_Clu_InhibitP", "CLU15", 0), - ("CF_Clu_InhibitN", "CLU15", 0), - ("CF_Clu_InhibitR", "CLU15", 0), + ("CF_Clu_Gear", "CLU15", 0), ] checks += [ ("CLU15", 5) diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 23645a125..56ae8e409 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -17,7 +17,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, values["CF_Lkas_ActToi"] = steer_req values["CF_Lkas_MsgCount"] = frame % 0x10 - if car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.SANTA_FE, CAR.IONIQ_EV_2020, CAR.KIA_SELTOS, CAR.ELANTRA_2021]: + if car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.SANTA_FE, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021]: values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1) values["CF_Lkas_LdwsOpt_USM"] = 2 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index c4ff372df..6f643f118 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 from cereal import car from selfdrive.config import Conversions as CV -from selfdrive.car.hyundai.values import CAR +from selfdrive.car.hyundai.values import CAR, EV_CAR, HYBRID_CAR from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint from selfdrive.car.interfaces import CarInterfaceBase @@ -77,6 +77,14 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.65 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + elif candidate == CAR.ELANTRA_HEV_2021: + ret.lateralTuning.pid.kf = 0.00005 + ret.mass = (3017. * CV.LB_TO_KG) + STD_CARGO_KG + ret.wheelbase = 2.72 + ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable + tire_stiffness_factor = 0.65 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.HYUNDAI_GENESIS: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG @@ -108,7 +116,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate in [CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020]: + elif candidate in [CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV]: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx ret.wheelbase = 2.7 @@ -116,7 +124,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - if candidate != CAR.IONIQ_EV_2020: + if candidate not in [CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV]: ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.VELOSTER: ret.lateralTuning.pid.kf = 0.00005 @@ -135,7 +143,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate == CAR.KIA_NIRO_EV: + elif candidate in [CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV]: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1737. + STD_CARGO_KG ret.wheelbase = 2.7 @@ -143,6 +151,8 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + if candidate == CAR.KIA_NIRO_HEV: + ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_SELTOS: ret.mass = 1337. + STD_CARGO_KG ret.wheelbase = 2.63 @@ -220,11 +230,17 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] # these cars require a special panda safety mode due to missing counters and checksums in the messages - if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, + if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_NIRO_EV, CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER, CAR.KIA_SELTOS, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA]: ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy + # set appropriate safety param for gas signal + if candidate in HYBRID_CAR: + ret.safetyParam = 2 + elif candidate in EV_CAR: + ret.safetyParam = 1 + ret.centerToFront = ret.wheelbase * 0.4 # TODO: get actual value, for now starting with reasonable value for @@ -236,7 +252,6 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - ret.enableCamera = True ret.enableBsm = 0x58b in fingerprint[0] return ret @@ -250,7 +265,6 @@ class CarInterface(CarInterfaceBase): ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False events = self.create_common_events(ret) - # TODO: addd abs(self.CS.angle_steers) > 90 to 'steerTempUnavailable' event # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index c69789598..f3fed2b19 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -7,7 +7,7 @@ Ecu = car.CarParams.Ecu # Steer torque limits class CarControllerParams: def __init__(self, CP): - if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE, CAR.SANTA_FE, CAR.VELOSTER, CAR.GENESIS_G70, CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021]: + if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE, CAR.SANTA_FE, CAR.VELOSTER, CAR.GENESIS_G70, CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021]: self.STEER_MAX = 384 else: self.STEER_MAX = 255 @@ -22,11 +22,13 @@ class CAR: # Hyundai ELANTRA = "HYUNDAI ELANTRA 2017" ELANTRA_2021 = "HYUNDAI ELANTRA 2021" + ELANTRA_HEV_2021 = "HYUNDAI ELANTRA HYBRID 2021" ELANTRA_GT_I30 = "HYUNDAI I30 N LINE 2019 & GT 2018 DCT" HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016" IONIQ = "HYUNDAI IONIQ HYBRID 2017-2019" IONIQ_EV_LTD = "HYUNDAI IONIQ ELECTRIC LIMITED 2019" IONIQ_EV_2020 = "HYUNDAI IONIQ ELECTRIC 2020" + IONIQ_PHEV = "HYUNDAI IONIQ PHEV 2020" KONA = "HYUNDAI KONA 2020" KONA_EV = "HYUNDAI KONA ELECTRIC 2019" SANTA_FE = "HYUNDAI SANTA FE 2019" @@ -38,6 +40,7 @@ class CAR: # Kia KIA_FORTE = "KIA FORTE E 2018 & GT 2021" KIA_NIRO_EV = "KIA NIRO EV 2020" + KIA_NIRO_HEV = "KIA NIRO HYBRID 2019" KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016" KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" KIA_SELTOS = "KIA SELTOS 2021" @@ -153,6 +156,23 @@ FINGERPRINTS = { FW_VERSIONS = { + CAR.IONIQ_PHEV: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\000AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\000AE MDPS C 1.00 1.01 56310/G2510 4APHC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\000AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6F6051\000\000\000\000\000\000\000\000', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U3J9051\000\000\xf1\0006U3H1_C2\000\0006U3J9051\000\000PAE0G16NL0\x82zT\xd2', + ], + }, CAR.IONIQ_EV_2020: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', @@ -195,6 +215,7 @@ FW_VERSIONS = { (Ecu.esp, 0x7d1, None): [ b'\xf1\x00DN ESC \a 106 \a\x01 58910-L0100', b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300\xf1\xa01.02', + b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300\xf1\xa01.03', @@ -206,6 +227,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x81HM6M1_0a0_F00', b'\xf1\x82DNBVN5GMCCXXXDCA', + b'\xf1\x82DNBWN5TMDCXXXG2E', b'\xf1\x82DNCVN5GMCCXXXG2B', b'\xf1\x87391162M003\xf1\xa0000F', b'\xf1\x87391162M003\xf1\xa00240', @@ -217,6 +239,7 @@ FW_VERSIONS = { b'\xf1\x00DN8 MDPS C 1.00 1.01 \x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00 4DNAC101', b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', + b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', b'\xf1\x87\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x00DN8 MDPS C 1.00 1.01 \x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00 4DNAC101\xf1\xa01.01', b'\xf1\x8756310-L0010\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101\xf1\xa01.01', b'\xf1\x8756310-L0210\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101\xf1\xa01.01', @@ -240,6 +263,7 @@ FW_VERSIONS = { b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x96\xa1\xf1\x92', b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB2\x00\x00\x00\x00\x00\x00\x08\xc9O:', + b'\xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5', b'\xf1\x87SALDBA3510954GJ3ww\x87xUUuWx\x88\x87\x88\x87w\x88wvfwfc_\xf9\xff\x98wO\xffl\xe0\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', b'\xf1\x87SALDBA3573534GJ3\x89\x98\x89\x88EUuWgwvwwwwww\x88\x87xTo\xfa\xff\x86f\x7f\xffo\x0e\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', b'\xf1\x87SALDBA3601464GJ3\x88\x88\x88\x88ffvggwvwvw\x87gww\x87wvo\xfb\xff\x98\x88\x7f\xffjJ\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', @@ -327,6 +351,7 @@ FW_VERSIONS = { b'\xf1\x87SBLWAA6622844GG0wwwwff\x86hwwwwx\x88\x87\x88\x88\x88\x88\x88\x98?\xfd\xff\xa9\x88\x7f\xffn\xe5\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS7u\x1e{\x1c', b'\xf1\x87SDJXAA7656854GG1DEtWUU\x85X\x88\x88\x98\x88w\x88\x87xx\x88\x87\x88\x96o\xfb\xff\x86f\x7f\xff.\xca\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4G24NS2\x00\x00\x00\x00', b'\xf1\x87SDKXAA2443414GG1vfvgwv\x87h\x88\x88\x88\x88ww\x87wwwww\x99_\xfc\xffvD?\xffl\xd2\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4G24NS6\x00\x00\x00\x00', + b'\xf1\x87SBLWAA4899564GG0VfvgUU\x85Xx\x88\x87\x88vfgf\x87wxwvO\xfb\xff\x97f\xb1\xffSB\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS7\x00\x00\x00\x00', ], }, CAR.KIA_STINGER: { @@ -360,13 +385,6 @@ FW_VERSIONS = { b'\xf1\x87WAJTE17552812CH4vfFffvfVeT5DwvvVVdFeegeg\x88\x88o\xff\x1a]\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00TCK2T20NB1\x19\xd2\x00\x94', ], }, - CAR.KIA_OPTIMA_H: { - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ',], - (Ecu.engine, 0x7e0, None): [b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00',], - (Ecu.eps, 0x7d4, None): [b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109',], - (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424',], - (Ecu.transmission, 0x7e1, None): [b"\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\xf4'\\\x91",], - }, CAR.PALISADE: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\000LX2_ SCC F-CUP 1.00 1.05 99110-S8100 \xf1\xa01.05', @@ -431,14 +449,24 @@ FW_VERSIONS = { ], }, CAR.VELOSTER: { - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', + b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', + ], (Ecu.esp, 0x7d1, None): [b'\xf1\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.engine, 0x7e0, None): [b'\x01TJS-JNU06F200H0A', ], + (Ecu.engine, 0x7e0, None): [ + b'\x01TJS-JNU06F200H0A', + b'\x01TJS-JDK06F200H0A', + ], (Ecu.eps, 0x7d4, None): [b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', ], - (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', + b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', + ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\xba\x02\xb8\x80', b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\x00\x00\x00\x00', + b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16KS2\016\xba\036\xa2', ], }, CAR.GENESIS_G70: { @@ -535,6 +563,24 @@ FW_VERSIONS = { b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', ], }, + CAR.KIA_NIRO_HEV: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6F4051\000\000\000\000\000\000\000\000', + ], + (Ecu.transmission, 0x7e1, None): [ + b"\xf1\x816U3J2051\000\000\xf1\0006U3H0_C2\000\0006U3J2051\000\000PDE0G16NS2\xf4\'\\\x91", + b'\xf1\x816U3J2051\000\000\xf1\0006U3H0_C2\000\0006U3J2051\000\000PDE0G16NS2\000\000\000\000', + ], + (Ecu.eps, 0x7D4, None): [ + b'\xf1\000DE MDPS C 1.00 1.09 56310G5301\000 4DEHC109', + ], + (Ecu.fwdCamera, 0x7C4, None): [ + b'\xf1\000DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', + ], + (Ecu.fwdRadar, 0x7D0, None): [ + b'\xf1\000DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', + ], + }, CAR.KIA_SELTOS: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110Q5100\xf1\000SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 \xf1\xa01.05',], (Ecu.esp, 0x7d1, None): [ @@ -543,6 +589,7 @@ FW_VERSIONS = { ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x81616D2051\000\000\000\000\000\000\000\000', + b'\xf1\x81616D5051\000\000\000\000\000\000\000\000', b'\001TSP2KNL06F100J0K', b'\001TSP2KNL06F200J0K', ], @@ -588,11 +635,28 @@ FW_VERSIONS = { b'\xf1\x87CXMQFM2135005JB2E\xb9\x89\x98W\xa9y\x97h\xa9\x98\x99wxvwh\x87\177\xffx\xff\xff\xff,,\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [b'\xf1\x82CNCWD0AMFCXCSFFA'], + }, + CAR.ELANTRA_HEV_2021: { + (Ecu.fwdCamera, 0x7c4, None) : [ + b'\xf1\000CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819' + ], + (Ecu.fwdRadar, 0x7d0, None) : [ + b'\xf1\000CNhe SCC FHCUP 1.00 1.01 99110-BY000 ' + ], + (Ecu.eps, 0x7d4, None) :[ + b'\xf1\x8756310/BY050\xf1\000CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102\xf1\xa01.02' + ], + (Ecu.transmission, 0x7e1, None) :[ + b'\xf1\x816U3K3051\000\000\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\xb9?A\xaa' + ], + (Ecu.engine, 0x7e0, None) : [ + b'\xf1\x816H6G5051\000\000\000\000\000\000\000\000' + ] } } CHECKSUM = { - "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021], + "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021], "6B": [CAR.KIA_SORENTO, CAR.HYUNDAI_GENESIS], } @@ -600,27 +664,31 @@ FEATURES = { # which message has the gear "use_cluster_gears": set([CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA]), "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_LF, CAR.VELOSTER]), - "use_elect_gears": set([CAR.KIA_NIRO_EV, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020]), + "use_elect_gears": set([CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021]), # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS]), + "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS]), } -EV_HYBRID = set([CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_NIRO_EV]) +HYBRID_CAR = set([CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_HEV]) # these cars use a different gas signal +EV_CAR = set([CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_NIRO_EV]) DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_2021: dbc_dict('hyundai_kia_generic', None), + CAR.ELANTRA_HEV_2021: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_GT_I30: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G70: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G80: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G90: dbc_dict('hyundai_kia_generic', None), CAR.HYUNDAI_GENESIS: dbc_dict('hyundai_kia_generic', None), + CAR.IONIQ_PHEV: dbc_dict('hyundai_kia_generic', None), CAR.IONIQ_EV_2020: dbc_dict('hyundai_kia_generic', None), CAR.IONIQ_EV_LTD: dbc_dict('hyundai_kia_generic', None), CAR.IONIQ: dbc_dict('hyundai_kia_generic', None), CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_NIRO_HEV: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), CAR.KIA_SELTOS: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index f049434bf..34c6c5a54 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -27,6 +27,8 @@ class CarInterfaceBase(): self.VM = VehicleModel(CP) self.frame = 0 + self.steer_warning = 0 + self.steering_unpressed = 0 self.low_speed_alert = False if CarState is not None: @@ -51,6 +53,10 @@ class CarInterfaceBase(): def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None): raise NotImplementedError + @staticmethod + def init(CP, logcan, sendcan): + pass + # returns a set of default params to avoid repetition in car specific params @staticmethod def get_std_params(candidate, fingerprint): @@ -63,12 +69,11 @@ class CarInterfaceBase(): ret.steerMaxV = [1.] ret.minSteerSpeed = 0. - # stock ACC by default - ret.enableCruise = True - ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this + ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars + ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this ret.steerRatioRear = 0. # no rear steering, at least on the listed cars aboveA ret.gasMaxBP = [0.] - ret.gasMaxV = [.5] # half max brake + ret.gasMaxV = [.5] # half max brake ret.brakeMaxBP = [0.] ret.brakeMaxV = [1.] ret.openpilotLongitudinalControl = False @@ -76,7 +81,7 @@ class CarInterfaceBase(): ret.minSpeedCan = 0.3 ret.stoppingBrakeRate = 0.2 # brake_travel/s while trying to stop ret.startingBrakeRate = 0.8 # brake_travel/s while releasing on restart - ret.stoppingControl = False + ret.stoppingControl = True ret.longitudinalTuning.deadzoneBP = [0.] ret.longitudinalTuning.deadzoneV = [0.] ret.longitudinalTuning.kpBP = [0.] @@ -93,14 +98,15 @@ class CarInterfaceBase(): def apply(self, c): raise NotImplementedError - def create_common_events(self, cs_out, extra_gears=[], gas_resume_speed=-1, pcm_enable=True): # pylint: disable=dangerous-default-value + def create_common_events(self, cs_out, extra_gears=None, gas_resume_speed=-1, pcm_enable=True): events = Events() if cs_out.doorOpen: events.add(EventName.doorOpen) if cs_out.seatbeltUnlatched: events.add(EventName.seatbeltNotLatched) - if cs_out.gearShifter != GearShifter.drive and cs_out.gearShifter not in extra_gears: + if cs_out.gearShifter != GearShifter.drive and (extra_gears is None or + cs_out.gearShifter not in extra_gears): events.add(EventName.wrongGear) if cs_out.gearShifter == GearShifter.reverse: events.add(EventName.reverseGear) @@ -119,13 +125,19 @@ class CarInterfaceBase(): if cs_out.cruiseState.nonAdaptive: events.add(EventName.wrongCruiseMode) + self.steer_warning = self.steer_warning + 1 if cs_out.steerWarning else 0 + self.steering_unpressed = 0 if cs_out.steeringPressed else self.steering_unpressed + 1 + + # Handle permanent and temporary steering faults if cs_out.steerError: events.add(EventName.steerUnavailable) elif cs_out.steerWarning: - if cs_out.steeringPressed: - events.add(EventName.steerTempUnavailableUserOverride) - else: + # only escalate to the harsher alert after the condition has + # persisted for 0.5s and we're certain that the user isn't overriding + if self.steering_unpressed > int(0.5/DT_CTRL) and self.steer_warning > int(0.5/DT_CTRL): events.add(EventName.steerTempUnavailable) + else: + events.add(EventName.steerTempUnavailableSilent) # Disable on rising edge of gas or brake. Also disable on brake when speed > 0. # Optionally allow to press gas at zero speed to resume. @@ -167,6 +179,8 @@ class CarStateBase: self.cruise_buttons = 0 self.left_blinker_cnt = 0 self.right_blinker_cnt = 0 + self.left_blinker_prev = False + self.right_blinker_prev = False # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) # R = 1e3 @@ -182,11 +196,37 @@ class CarStateBase: v_ego_x = self.v_ego_kf.update(v_ego_raw) return float(v_ego_x[0]), float(v_ego_x[1]) - def update_blinker(self, blinker_time: int, left_blinker_lamp: bool, right_blinker_lamp: bool): + def update_blinker_from_lamp(self, blinker_time: int, left_blinker_lamp: bool, right_blinker_lamp: bool): + """Update blinkers from lights. Enable output when light was seen within the last `blinker_time` + iterations""" + # TODO: Handle case when switching direction. Now both blinkers can be on at the same time self.left_blinker_cnt = blinker_time if left_blinker_lamp else max(self.left_blinker_cnt - 1, 0) self.right_blinker_cnt = blinker_time if right_blinker_lamp else max(self.right_blinker_cnt - 1, 0) return self.left_blinker_cnt > 0, self.right_blinker_cnt > 0 + def update_blinker_from_stalk(self, blinker_time: int, left_blinker_stalk: bool, right_blinker_stalk: bool): + """Update blinkers from stalk position. When stalk is seen the blinker will be on for at least blinker_time, + or until the stalk is turned off, whichever is longer. If the opposite stalk direction is seen the blinker + is forced to the other side. On a rising edge of the stalk the timeout is reset.""" + + if left_blinker_stalk: + self.right_blinker_cnt = 0 + if not self.left_blinker_prev: + self.left_blinker_cnt = blinker_time + + if right_blinker_stalk: + self.left_blinker_cnt = 0 + if not self.right_blinker_prev: + self.right_blinker_cnt = blinker_time + + self.left_blinker_cnt = max(self.left_blinker_cnt - 1, 0) + self.right_blinker_cnt = max(self.right_blinker_cnt - 1, 0) + + self.left_blinker_prev = left_blinker_stalk + self.right_blinker_prev = right_blinker_stalk + + return bool(left_blinker_stalk or self.left_blinker_cnt > 0), bool(right_blinker_stalk or self.right_blinker_cnt > 0) + @staticmethod def parse_gear_shifter(gear: str) -> car.CarState.GearShifter: d: Dict[str, car.CarState.GearShifter] = { diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index c79ff9b3a..dfc1c12bf 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -20,11 +20,11 @@ class CarInterface(CarInterfaceBase): ret.carName = "mazda" ret.safetyModel = car.CarParams.SafetyModel.mazda - - ret.dashcamOnly = True - ret.radarOffCan = True + ret.communityFeature = True + ret.dashcamOnly = True + ret.steerActuatorDelay = 0.1 ret.steerRateCost = 1.0 ret.steerLimitTimer = 0.8 @@ -37,7 +37,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.019]] ret.lateralTuning.pid.kf = 0.00006 - elif candidate == CAR.CX9: + elif candidate in [CAR.CX9, CAR.CX9_2021]: ret.mass = 4217 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 3.1 ret.steerRatio = 17.6 @@ -73,8 +73,6 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - ret.enableCamera = True - return ret # returns a car.CarState diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 6ad1da04a..c49b8c86e 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -8,19 +8,20 @@ Ecu = car.CarParams.Ecu # Steer torque limits class CarControllerParams: - STEER_MAX = 600 # max_steer 2048 - STEER_STEP = 1 # how often we update the steer cmd + STEER_MAX = 800 # theoretical max_steer 2047 STEER_DELTA_UP = 10 # torque increase per refresh - STEER_DELTA_DOWN = 20 # torque decrease per refresh + STEER_DELTA_DOWN = 25 # torque decrease per refresh STEER_DRIVER_ALLOWANCE = 15 # allowed driver torque before start limiting STEER_DRIVER_MULTIPLIER = 1 # weight driver torque STEER_DRIVER_FACTOR = 1 # from dbc + STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor class CAR: CX5 = "MAZDA CX-5" CX9 = "MAZDA CX-9" MAZDA3 = "MAZDA 3" MAZDA6 = "MAZDA 6" + CX9_2021 = "Mazda CX-9 2021" # No Steer Lockout class LKAS_LIMITS: STEER_THRESHOLD = 15 @@ -39,19 +40,25 @@ FW_VERSIONS = { CAR.CX5: { (Ecu.eps, 0x730, None): [ b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -64,14 +71,20 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x706, None): [ b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, @@ -79,44 +92,52 @@ FW_VERSIONS = { CAR.CX9 : { (Ecu.eps, 0x730, None): [ b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x760, None): [ b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, CAR.MAZDA3: { (Ecu.eps, 0x730, None): [ - b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -156,6 +177,27 @@ FW_VERSIONS = { (Ecu.transmission, 0x7e1, None): [ b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], + }, + + CAR.CX9_2021 : { + (Ecu.eps, 0x730, None): [ + b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x760, None): [ + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], } } @@ -165,6 +207,11 @@ DBC = { CAR.CX9: dbc_dict('mazda_2017', None), CAR.MAZDA3: dbc_dict('mazda_2017', None), CAR.MAZDA6: dbc_dict('mazda_2017', None), + CAR.CX9_2021: dbc_dict('mazda_2017', None), } -GEN1 = [ CAR.CX5, CAR.CX9, CAR.MAZDA3, CAR.MAZDA6 ] +# Gen 1 hardware: same CAN messages and same camera +GEN1 = set([CAR.CX5, CAR.CX9, CAR.CX9_2021, CAR.MAZDA3, CAR.MAZDA6]) + +# Cars with a steering lockout +STEER_LOCKOUT_CAR = set([CAR.CX5, CAR.CX9, CAR.MAZDA3, CAR.MAZDA6]) diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py index 8f763f358..41ba9f659 100644 --- a/selfdrive/car/nissan/carcontroller.py +++ b/selfdrive/car/nissan/carcontroller.py @@ -31,7 +31,7 @@ class CarController(): lkas_hud_info_msg = CS.lkas_hud_info_msg apply_angle = actuators.steeringAngleDeg - steer_hud_alert = 1 if hud_alert == VisualAlert.steerRequired else 0 + steer_hud_alert = 1 if hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw] else 0 if enabled: # # windup slower diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 30f4e94f9..d85abd770 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -24,7 +24,6 @@ class CarInterface(CarInterfaceBase): ret.communityFeature = True ret.steerLimitAlert = False - ret.enableCamera = True ret.steerRateCost = 0.5 ret.steerActuatorDelay = 0.1 @@ -46,7 +45,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.824 ret.centerToFront = ret.wheelbase * 0.44 ret.steerRatio = 17 - + ret.steerControlType = car.CarParams.SteerControlType.angle ret.radarOffCan = True diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index 8ec957a65..80ac2542a 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -15,7 +15,7 @@ class CarController(): self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) - def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_line, right_line): + def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): can_sends = [] @@ -69,7 +69,7 @@ class CarController(): self.es_distance_cnt = CS.es_distance_msg["Counter"] if self.es_lkas_cnt != CS.es_lkas_msg["Counter"]: - can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, visual_alert, left_line, right_line)) + can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart)) self.es_lkas_cnt = CS.es_lkas_msg["Counter"] return can_sends diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index 888c370eb..d2fa0c795 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -33,8 +33,8 @@ class CarState(CarStateBase): ret.standstill = ret.vEgoRaw < 0.01 # continuous blinker signals for assisted lane change - ret.leftBlinker, ret.rightBlinker = self.update_blinker(50, cp.vl["Dashlights"]["LEFT_BLINKER"], - cp.vl["Dashlights"]["RIGHT_BLINKER"]) + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp( + 50, cp.vl["Dashlights"]["LEFT_BLINKER"], cp.vl["Dashlights"]["RIGHT_BLINKER"]) if self.CP.enableBsm: ret.leftBlindspot = (cp.vl["BSD_RCTA"]["L_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["L_APPROACHING"] == 1) diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index bb8669fb1..436dda8d1 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -28,8 +28,6 @@ class CarInterface(CarInterfaceBase): ret.communityFeature = True ret.dashcamOnly = candidate in PREGLOBAL_CARS - ret.enableCamera = True - ret.steerRateCost = 0.7 ret.steerLimitTimer = 0.4 @@ -122,6 +120,6 @@ class CarInterface(CarInterfaceBase): def apply(self, c): can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert, - c.hudControl.leftLaneVisible, c.hudControl.rightLaneVisible) + c.hudControl.leftLaneVisible, c.hudControl.rightLaneVisible, c.hudControl.leftLaneDepart, c.hudControl.rightLaneDepart) self.frame += 1 return can_sends diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py index 672b6873b..5a98ea554 100644 --- a/selfdrive/car/subaru/subarucan.py +++ b/selfdrive/car/subaru/subarucan.py @@ -27,12 +27,20 @@ def create_es_distance(packer, es_distance_msg, pcm_cancel_cmd): return packer.make_can_msg("ES_Distance", 0, values) -def create_es_lkas(packer, es_lkas_msg, visual_alert, left_line, right_line): +def create_es_lkas(packer, es_lkas_msg, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): values = copy.copy(es_lkas_msg) if visual_alert == VisualAlert.steerRequired: values["Keep_Hands_On_Wheel"] = 1 + # Ensure we don't overwrite potentially more important alerts from stock (e.g. FCW) + if visual_alert == VisualAlert.ldw and values["LKAS_Alert"] == 0: + if left_lane_depart: + values["LKAS_Alert"] = 12 # Left lane departure dash alert + + elif right_lane_depart: + values["LKAS_Alert"] = 11 # Right lane departure dash alert + values["LKAS_Left_Line_Visible"] = int(left_line) values["LKAS_Right_Line_Visible"] = int(right_line) diff --git a/selfdrive/controls/lib/longitudinal_mpc/__init__.py b/selfdrive/car/tesla/__init__.py similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/__init__.py rename to selfdrive/car/tesla/__init__.py diff --git a/selfdrive/car/tesla/carcontroller.py b/selfdrive/car/tesla/carcontroller.py new file mode 100644 index 000000000..df53b9dd9 --- /dev/null +++ b/selfdrive/car/tesla/carcontroller.py @@ -0,0 +1,53 @@ +from common.numpy_fast import clip, interp +from selfdrive.car.tesla.teslacan import TeslaCAN +from opendbc.can.packer import CANPacker +from selfdrive.car.tesla.values import CANBUS, CarControllerParams + +class CarController(): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.last_angle = 0 + self.packer = CANPacker(dbc_name) + self.tesla_can = TeslaCAN(dbc_name, self.packer) + + def update(self, enabled, CS, frame, actuators, cruise_cancel): + can_sends = [] + + # Temp disable steering on a hands_on_fault, and allow for user override + hands_on_fault = (CS.steer_warning == "EAC_ERROR_HANDS_ON" and CS.hands_on_level >= 3) + lkas_enabled = enabled and (not hands_on_fault) + + if lkas_enabled: + apply_angle = actuators.steeringAngleDeg + + # Angular rate limit based on speed + steer_up = (self.last_angle * apply_angle > 0. and abs(apply_angle) > abs(self.last_angle)) + rate_limit = CarControllerParams.RATE_LIMIT_UP if steer_up else CarControllerParams.RATE_LIMIT_DOWN + max_angle_diff = interp(CS.out.vEgo, rate_limit.speed_points, rate_limit.max_angle_diff_points) + apply_angle = clip(apply_angle, (self.last_angle - max_angle_diff), (self.last_angle + max_angle_diff)) + + # To not fault the EPS + apply_angle = clip(apply_angle, (CS.out.steeringAngleDeg - 20), (CS.out.steeringAngleDeg + 20)) + else: + apply_angle = CS.out.steeringAngleDeg + + self.last_angle = apply_angle + can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, frame)) + + # Cancel on user steering override, since there is no steering torque blending + if hands_on_fault: + cruise_cancel = True + + # Cancel when openpilot is not enabled anymore + if not enabled and bool(CS.out.cruiseState.enabled): + cruise_cancel = True + + if ((frame % 10) == 0 and cruise_cancel): + # Spam every possible counter value, otherwise it might not be accepted + for counter in range(16): + can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, cruise_cancel, CANBUS.chassis, counter)) + can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, cruise_cancel, CANBUS.autopilot, counter)) + + # TODO: HUD control + + return can_sends diff --git a/selfdrive/car/tesla/carstate.py b/selfdrive/car/tesla/carstate.py new file mode 100644 index 000000000..204152611 --- /dev/null +++ b/selfdrive/car/tesla/carstate.py @@ -0,0 +1,181 @@ +import copy +from cereal import car +from selfdrive.car.tesla.values import DBC, CANBUS, GEAR_MAP, DOORS, BUTTONS +from selfdrive.car.interfaces import CarStateBase +from opendbc.can.parser import CANParser +from opendbc.can.can_define import CANDefine +from selfdrive.config import Conversions as CV + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + self.button_states = {button.event_type: False for button in BUTTONS} + self.can_define = CANDefine(DBC[CP.carFingerprint]['chassis']) + + # Needed by carcontroller + self.msg_stw_actn_req = None + self.hands_on_level = 0 + self.steer_warning = None + + def update(self, cp, cp_cam): + ret = car.CarState.new_message() + + # Vehicle speed + ret.vEgoRaw = cp.vl["ESP_B"]["ESP_vehicleSpeed"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = (ret.vEgo < 0.1) + + # Gas pedal + ret.gas = cp.vl["DI_torque1"]["DI_pedalPos"] / 100.0 + ret.gasPressed = (ret.gas > 0) + + # Brake pedal + ret.brake = 0 + ret.brakePressed = bool(cp.vl["BrakeMessage"]["driverBrakeStatus"] != 1) + + # Steering wheel + self.hands_on_level = cp.vl["EPAS_sysStatus"]["EPAS_handsOnLevel"] + self.steer_warning = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacErrorCode"].get(int(cp.vl["EPAS_sysStatus"]["EPAS_eacErrorCode"]), None) + steer_status = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacStatus"].get(int(cp.vl["EPAS_sysStatus"]["EPAS_eacStatus"]), None) + + ret.steeringAngleDeg = -cp.vl["EPAS_sysStatus"]["EPAS_internalSAS"] + ret.steeringRateDeg = -cp.vl["STW_ANGLHP_STAT"]["StW_AnglHP_Spd"] # This is from a different angle sensor, and at different rate + ret.steeringTorque = -cp.vl["EPAS_sysStatus"]["EPAS_torsionBarTorque"] + ret.steeringPressed = (self.hands_on_level > 0) + ret.steerError = steer_status == "EAC_FAULT" + ret.steerWarning = self.steer_warning in ["EAC_ERROR_MAX_SPEED", "EAC_ERROR_MIN_SPEED", "EAC_ERROR_TMP_FAULT", "SNA"] # TODO: not sure if this list is complete + + # Cruise state + cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) + speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) + + acc_enabled = (cruise_state in ["ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL"]) + + ret.cruiseState.enabled = acc_enabled + if speed_units == "KPH": + ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS + elif speed_units == "MPH": + ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.MPH_TO_MS + ret.cruiseState.available = ((cruise_state == "STANDBY") or ret.cruiseState.enabled) + ret.cruiseState.standstill = (cruise_state == "STANDSTILL") + + # Gear + ret.gearShifter = GEAR_MAP[self.can_define.dv["DI_torque2"]["DI_gear"].get(int(cp.vl["DI_torque2"]["DI_gear"]), "DI_GEAR_INVALID")] + + # Buttons + buttonEvents = [] + for button in BUTTONS: + state = (cp.vl[button.can_addr][button.can_msg] in button.values) + if self.button_states[button.event_type] != state: + event = car.CarState.ButtonEvent.new_message() + event.type = button.event_type + event.pressed = state + buttonEvents.append(event) + self.button_states[button.event_type] = state + 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]) + + # Blinkers + ret.leftBlinker = (cp.vl["GTW_carState"]["BC_indicatorLStatus"] == 1) + ret.rightBlinker = (cp.vl["GTW_carState"]["BC_indicatorRStatus"] == 1) + + # Seatbelt + ret.seatbeltUnlatched = (cp.vl["SDM1"]["SDM_bcklDrivStatus"] != 1) + + # TODO: blindspot + + # Messages needed by carcontroller + self.msg_stw_actn_req = copy.copy(cp.vl["STW_ACTN_RQ"]) + + return ret + + @staticmethod + def get_can_parser(CP): + signals = [ + # sig_name, sig_address, default + ("ESP_vehicleSpeed", "ESP_B", 0), + ("DI_pedalPos", "DI_torque1", 0), + ("DI_brakePedal", "DI_torque2", 0), + ("StW_AnglHP", "STW_ANGLHP_STAT", 0), + ("StW_AnglHP_Spd", "STW_ANGLHP_STAT", 0), + ("EPAS_handsOnLevel", "EPAS_sysStatus", 0), + ("EPAS_torsionBarTorque", "EPAS_sysStatus", 0), + ("EPAS_internalSAS", "EPAS_sysStatus", 0), + ("EPAS_eacStatus", "EPAS_sysStatus", 1), + ("EPAS_eacErrorCode", "EPAS_sysStatus", 0), + ("DI_cruiseState", "DI_state", 0), + ("DI_digitalSpeed", "DI_state", 0), + ("DI_speedUnits", "DI_state", 0), + ("DI_gear", "DI_torque2", 0), + ("DOOR_STATE_FL", "GTW_carState", 1), + ("DOOR_STATE_FR", "GTW_carState", 1), + ("DOOR_STATE_RL", "GTW_carState", 1), + ("DOOR_STATE_RR", "GTW_carState", 1), + ("DOOR_STATE_FrontTrunk", "GTW_carState", 1), + ("BOOT_STATE", "GTW_carState", 1), + ("BC_indicatorLStatus", "GTW_carState", 1), + ("BC_indicatorRStatus", "GTW_carState", 1), + ("SDM_bcklDrivStatus", "SDM1", 0), + ("driverBrakeStatus", "BrakeMessage", 0), + + # We copy this whole message when spamming cancel + ("SpdCtrlLvr_Stat", "STW_ACTN_RQ", 0), + ("VSL_Enbl_Rq", "STW_ACTN_RQ", 0), + ("SpdCtrlLvrStat_Inv", "STW_ACTN_RQ", 0), + ("DTR_Dist_Rq", "STW_ACTN_RQ", 0), + ("TurnIndLvr_Stat", "STW_ACTN_RQ", 0), + ("HiBmLvr_Stat", "STW_ACTN_RQ", 0), + ("WprWashSw_Psd", "STW_ACTN_RQ", 0), + ("WprWash_R_Sw_Posn_V2", "STW_ACTN_RQ", 0), + ("StW_Lvr_Stat", "STW_ACTN_RQ", 0), + ("StW_Cond_Flt", "STW_ACTN_RQ", 0), + ("StW_Cond_Psd", "STW_ACTN_RQ", 0), + ("HrnSw_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw00_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw01_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw02_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw03_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw04_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw05_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw06_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw07_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw08_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw09_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw10_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw11_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw12_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw13_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw14_Psd", "STW_ACTN_RQ", 0), + ("StW_Sw15_Psd", "STW_ACTN_RQ", 0), + ("WprSw6Posn", "STW_ACTN_RQ", 0), + ("MC_STW_ACTN_RQ", "STW_ACTN_RQ", 0), + ("CRC_STW_ACTN_RQ", "STW_ACTN_RQ", 0), + ] + + checks = [ + # sig_address, frequency + ("ESP_B", 50), + ("DI_torque1", 100), + ("DI_torque2", 100), + ("STW_ANGLHP_STAT", 100), + ("EPAS_sysStatus", 25), + ("DI_state", 10), + ("STW_ACTN_RQ", 10), + ("GTW_carState", 10), + ("SDM1", 10), + ("BrakeMessage", 50), + ] + + return CANParser(DBC[CP.carFingerprint]['chassis'], signals, checks, CANBUS.chassis) + + @staticmethod + def get_cam_can_parser(CP): + signals = [ + # sig_name, sig_address, default + ] + checks = [ + # sig_address, frequency + ] + return CANParser(DBC[CP.carFingerprint]['chassis'], signals, checks, CANBUS.autopilot) diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py new file mode 100755 index 000000000..b3564c10c --- /dev/null +++ b/selfdrive/car/tesla/interface.py @@ -0,0 +1,61 @@ +#!/usr/bin/env python3 +from cereal import car +from selfdrive.car.tesla.values import CAR +from selfdrive.car import STD_CARGO_KG, gen_empty_fingerprint, scale_rot_inertia, scale_tire_stiffness +from selfdrive.car.interfaces import CarInterfaceBase + + +class CarInterface(CarInterfaceBase): + @staticmethod + def compute_gb(accel, speed): + # TODO: is this correct? + return accel + + @staticmethod + def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None): + ret = CarInterfaceBase.get_std_params(candidate, fingerprint) + ret.carName = "tesla" + ret.safetyModel = car.CarParams.SafetyModel.tesla + + # There is no safe way to do steer blending with user torque, + # so the steering behaves like autopilot. This is not + # how openpilot should be, hence dashcamOnly + ret.dashcamOnly = True + + ret.steerControlType = car.CarParams.SteerControlType.angle + ret.openpilotLongitudinalControl = False + ret.communityFeature = True + + ret.steerActuatorDelay = 0.1 + ret.steerRateCost = 0.5 + + if candidate in [CAR.AP2_MODELS, CAR.AP1_MODELS]: + ret.mass = 2100. + STD_CARGO_KG + ret.wheelbase = 2.959 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 13.5 + else: + raise ValueError(f"Unsupported car: {candidate}") + + ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) + ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront) + + return ret + + def update(self, c, can_strings): + self.cp.update_strings(can_strings) + self.cp_cam.update_strings(can_strings) + + ret = self.CS.update(self.cp, self.cp_cam) + ret.canValid = self.cp.can_valid and self.cp_cam.can_valid + + events = self.create_common_events(ret) + + ret.events = events.to_msg() + self.CS.out = ret.as_reader() + return self.CS.out + + def apply(self, c): + can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.cancel) + self.frame += 1 + return can_sends diff --git a/selfdrive/car/tesla/radar_interface.py b/selfdrive/car/tesla/radar_interface.py new file mode 100755 index 000000000..b2f765113 --- /dev/null +++ b/selfdrive/car/tesla/radar_interface.py @@ -0,0 +1,5 @@ +#!/usr/bin/env python3 +from selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/selfdrive/car/tesla/teslacan.py b/selfdrive/car/tesla/teslacan.py new file mode 100644 index 000000000..0dee8b182 --- /dev/null +++ b/selfdrive/car/tesla/teslacan.py @@ -0,0 +1,41 @@ +import copy +import crcmod +from opendbc.can.can_define import CANDefine +from selfdrive.car.tesla.values import CANBUS + + +class TeslaCAN: + def __init__(self, dbc_name, packer): + self.can_define = CANDefine(dbc_name) + self.packer = packer + self.crc = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) + + @staticmethod + def checksum(msg_id, dat): + # TODO: get message ID from name instead + ret = (msg_id & 0xFF) + ((msg_id >> 8) & 0xFF) + ret += sum(dat) + return ret & 0xFF + + def create_steering_control(self, angle, enabled, frame): + values = { + "DAS_steeringAngleRequest": -angle, + "DAS_steeringHapticRequest": 0, + "DAS_steeringControlType": 1 if enabled else 0, + "DAS_steeringControlCounter": (frame % 16), + } + + data = self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values)[2] + values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) + return self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values) + + def create_action_request(self, msg_stw_actn_req, cancel, bus, counter): + values = copy.copy(msg_stw_actn_req) + + if cancel: + values["SpdCtrlLvr_Stat"] = 1 + values["MC_STW_ACTN_RQ"] = counter + + data = self.packer.make_can_msg("STW_ACTN_RQ", bus, values)[2] + values["CRC_STW_ACTN_RQ"] = self.crc(data[:7]) + return self.packer.make_can_msg("STW_ACTN_RQ", bus, values) diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py new file mode 100644 index 000000000..2a7cf9e50 --- /dev/null +++ b/selfdrive/car/tesla/values.py @@ -0,0 +1,61 @@ +# flake8: noqa + +from collections import namedtuple +from selfdrive.car import dbc_dict +from cereal import car + +Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) +AngleRateLimit = namedtuple('AngleRateLimit', ['speed_points', 'max_angle_diff_points']) + +class CAR: + AP1_MODELS = 'TESLA AP1 MODEL S' + AP2_MODELS = 'TESLA AP2 MODEL S' + +FINGERPRINTS = { + CAR.AP2_MODELS: [ + { + 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 277: 6, 280: 6, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 518: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 577: 8, 582: 5, 583: 8, 584: 4, 585: 8, 590: 8, 601: 8, 606: 8, 608: 1, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 692: 8, 693: 8, 695: 8, 696: 8, 697: 8, 699: 8, 700: 8, 701: 8, 702: 8, 703: 8, 704: 8, 708: 8, 709: 8, 710: 8, 711: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 811: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 845: 8, 846: 5, 848: 8, 852: 8, 853: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 876: 8, 877: 8, 879: 8, 880: 8, 882: 8, 884: 8, 888: 8, 893: 8, 894: 8, 901: 6, 904: 3, 905: 8, 906: 8, 908: 2, 909: 8, 910: 8, 912: 8, 920: 8, 921: 8, 925: 4, 926: 6, 936: 8, 941: 8, 949: 8, 952: 8, 953: 6, 968: 8, 969: 6, 970: 8, 971: 8, 977: 8, 984: 8, 987: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1007: 8, 1008: 8, 1010: 6, 1014: 1, 1015: 8, 1016: 8, 1017: 8, 1018: 8, 1020: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1049: 8, 1061: 8, 1064: 8, 1065: 8, 1070: 8, 1080: 8, 1081: 8, 1097: 8, 1113: 8, 1129: 8, 1145: 8, 1160: 4, 1177: 8, 1281: 8, 1328: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1353: 8, 1368: 8, 1412: 8, 1436: 8, 1476: 8, 1481: 8, 1497: 8, 1513: 8, 1519: 8, 1601: 8, 1605: 8, 1617: 8, 1621: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1824: 8, 1828: 8, 1831: 8, 1832: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2043: 5, 2045: 4 + }, + ], + CAR.AP1_MODELS: [ + { + 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 267: 5, 277: 6, 280: 6, 283: 5, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 577: 8, 582: 5, 584: 4, 585: 8, 590: 8, 606: 8, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 660: 5, 693: 8, 696: 8, 697: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 809: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 841: 8, 845: 8, 846: 5, 852: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 873: 8, 877: 8, 878: 8, 879: 8, 880: 8, 884: 8, 888: 8, 889: 8, 893: 8, 896: 8, 901: 6, 904: 3, 905: 8, 908: 2, 909: 8, 920: 8, 921: 8, 925: 4, 936: 8, 937: 8, 941: 8, 949: 8, 952: 8, 953: 6, 957: 8, 968: 8, 973: 8, 984: 8, 987: 8, 989: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1016: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1064: 8, 1070: 8, 1080: 8, 1160: 4, 1281: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1368: 8, 1412: 8, 1436: 8, 1465: 8, 1476: 8, 1497: 8, 1524: 8, 1527: 8, 1601: 8, 1605: 8, 1611: 8, 1614: 8, 1617: 8, 1621: 8, 1627: 8, 1630: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1848: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2043: 5, 2045: 4 + }, + ], +} + +DBC = { + CAR.AP2_MODELS: dbc_dict(None, 'tesla_radar', chassis_dbc='tesla_can'), + CAR.AP1_MODELS: dbc_dict(None, 'tesla_radar', chassis_dbc='tesla_can'), +} + +class CANBUS: + chassis = 0 + autopilot = 2 + radar = 1 + +GEAR_MAP = { + "DI_GEAR_INVALID": car.CarState.GearShifter.unknown, + "DI_GEAR_P": car.CarState.GearShifter.park, + "DI_GEAR_R": car.CarState.GearShifter.reverse, + "DI_GEAR_N": car.CarState.GearShifter.neutral, + "DI_GEAR_D": car.CarState.GearShifter.drive, + "DI_GEAR_SNA": car.CarState.GearShifter.unknown, +} + +DOORS = ["DOOR_STATE_FL", "DOOR_STATE_FR", "DOOR_STATE_RL", "DOOR_STATE_RR", "DOOR_STATE_FrontTrunk", "BOOT_STATE"] + +# Make sure the message and addr is also in the CAN parser! +BUTTONS = [ + Button(car.CarState.ButtonEvent.Type.leftBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [1]), + Button(car.CarState.ButtonEvent.Type.rightBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [2]), + Button(car.CarState.ButtonEvent.Type.accelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [4, 16]), + Button(car.CarState.ButtonEvent.Type.decelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [8, 32]), + Button(car.CarState.ButtonEvent.Type.cancel, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [2]), + Button(car.CarState.ButtonEvent.Type.resumeCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [1]), +] + +class CarControllerParams: + RATE_LIMIT_UP = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., .8, .15]) + RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4]) + diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 1bc18efb7..42c47f1b0 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -4,7 +4,7 @@ from selfdrive.car import apply_toyota_steer_torque_limits, create_gas_command, from selfdrive.car.toyota.toyotacan import create_steer_command, create_ui_command, \ create_accel_command, create_acc_cancel_command, \ create_fcw_command, create_lta_steer_command -from selfdrive.car.toyota.values import Ecu, CAR, STATIC_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \ +from selfdrive.car.toyota.values import CAR, STATIC_DSU_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \ MIN_ACC_SPEED, PEDAL_HYST_GAP, CarControllerParams from opendbc.can.packer import CANPacker @@ -36,12 +36,6 @@ class CarController(): self.steer_rate_limited = False self.use_interceptor = False - self.fake_ecus = set() - if CP.enableCamera: - self.fake_ecus.add(Ecu.fwdCamera) - if CP.enableDsu: - self.fake_ecus.add(Ecu.dsu) - self.packer = CANPacker(dbc_name) def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, hud_alert, @@ -104,27 +98,26 @@ class CarController(): # toyota can trace shows this message at 42Hz, with counter adding alternatively 1 and 2; # sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed # on consecutive messages - if Ecu.fwdCamera in self.fake_ecus: - can_sends.append(create_steer_command(self.packer, apply_steer, apply_steer_req, frame)) - if frame % 2 == 0 and CS.CP.carFingerprint in TSS2_CAR: - can_sends.append(create_lta_steer_command(self.packer, 0, 0, frame // 2)) + can_sends.append(create_steer_command(self.packer, apply_steer, apply_steer_req, frame)) + if frame % 2 == 0 and CS.CP.carFingerprint in TSS2_CAR: + can_sends.append(create_lta_steer_command(self.packer, 0, 0, frame // 2)) - # LTA mode. Set ret.steerControlType = car.CarParams.SteerControlType.angle and whitelist 0x191 in the panda - # if frame % 2 == 0: - # can_sends.append(create_steer_command(self.packer, 0, 0, frame // 2)) - # can_sends.append(create_lta_steer_command(self.packer, actuators.steeringAngleDeg, apply_steer_req, frame // 2)) + # LTA mode. Set ret.steerControlType = car.CarParams.SteerControlType.angle and whitelist 0x191 in the panda + # if frame % 2 == 0: + # can_sends.append(create_steer_command(self.packer, 0, 0, frame // 2)) + # can_sends.append(create_lta_steer_command(self.packer, actuators.steeringAngleDeg, apply_steer_req, frame // 2)) # we can spam can to cancel the system even if we are using lat only control - if (frame % 3 == 0 and CS.CP.openpilotLongitudinalControl) or (pcm_cancel_cmd and Ecu.fwdCamera in self.fake_ecus): + if (frame % 3 == 0 and CS.CP.openpilotLongitudinalControl) or pcm_cancel_cmd: lead = lead or CS.out.vEgo < 12. # at low speed we always assume the lead is present do ACC can be engaged # Lexus IS uses a different cancellation message if pcm_cancel_cmd and CS.CP.carFingerprint == CAR.LEXUS_IS: can_sends.append(create_acc_cancel_command(self.packer)) elif CS.CP.openpilotLongitudinalControl: - can_sends.append(create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead)) + can_sends.append(create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type)) else: - can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead)) + can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead, CS.acc_type)) if frame % 2 == 0 and CS.CP.enableGasInterceptor: # send exactly zero if gas cmd is zero. Interceptor will send the max between read value and gas cmd. @@ -135,7 +128,7 @@ class CarController(): # - there is something to display # - there is something to stop displaying fcw_alert = hud_alert == VisualAlert.fcw - steer_alert = hud_alert == VisualAlert.steerRequired + steer_alert = hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw] send_ui = False if ((fcw_alert or steer_alert) and not self.alert_active) or \ @@ -146,16 +139,16 @@ class CarController(): # forcing the pcm to disengage causes a bad fault sound so play a good sound instead send_ui = True - if (frame % 100 == 0 or send_ui) and Ecu.fwdCamera in self.fake_ecus: + if (frame % 100 == 0 or send_ui): can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, left_line, right_line, left_lane_depart, right_lane_depart)) - if frame % 100 == 0 and Ecu.dsu in self.fake_ecus: + if frame % 100 == 0 and CS.CP.enableDsu: can_sends.append(create_fcw_command(self.packer, fcw_alert)) #*** static msgs *** - for (addr, ecu, cars, bus, fr_step, vl) in STATIC_MSGS: - if frame % fr_step == 0 and ecu in self.fake_ecus and CS.CP.carFingerprint in cars: + for (addr, cars, bus, fr_step, vl) in STATIC_DSU_MSGS: + if frame % fr_step == 0 and CS.CP.enableDsu and CS.CP.carFingerprint in cars: can_sends.append(make_can_msg(addr, vl, bus)) return can_sends diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 1f5cae59f..952e39ce2 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -4,7 +4,7 @@ from opendbc.can.can_define import CANDefine from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser from selfdrive.config import Conversions as CV -from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR +from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, TSS2_CAR class CarState(CarStateBase): @@ -20,6 +20,9 @@ class CarState(CarStateBase): self.accurate_steer_angle_seen = False self.angle_offset = 0. + self.low_speed_lockout = False + self.acc_type = 1 + def update(self, cp, cp_cam): ret = car.CarState.new_message() @@ -74,11 +77,21 @@ class CarState(CarStateBase): if self.CP.carFingerprint == CAR.LEXUS_IS: ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS - self.low_speed_lockout = False else: ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS + + if self.CP.carFingerprint in TSS2_CAR: + self.acc_type = cp_cam.vl["ACC_CONTROL"]["ACC_TYPE"] + + # some TSS2 cars have low speed lockout permanently set, so ignore on those cars + # these cars are identified by an ACC_TYPE value of 2. + # TODO: it may be possible to avoid the lockout and gain stop and go if you + # send your own ACC_CONTROL msg on startup with ACC_TYPE set to 1 + if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint != CAR.LEXUS_IS) or \ + (self.CP.carFingerprint in TSS2_CAR and self.acc_type == 1): self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2 + self.pcm_acc_status = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] if self.CP.carFingerprint in NO_STOP_TIMER_CAR or self.CP.enableGasInterceptor: # ignore standstill in hybrid vehicles, since pcm allows to restart without @@ -183,7 +196,7 @@ class CarState(CarStateBase): signals = [ ("FORCE", "PRE_COLLISION", 0), - ("PRECOLLISION_ACTIVE", "PRE_COLLISION", 0) + ("PRECOLLISION_ACTIVE", "PRE_COLLISION", 0), ] # use steering message to check if panda is connected to frc @@ -192,4 +205,8 @@ class CarState(CarStateBase): ("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent ] + if CP.carFingerprint in TSS2_CAR: + signals.append(("ACC_TYPE", "ACC_CONTROL", 0)) + checks.append(("ACC_CONTROL", 33)) + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 6408ad01a..dd1543246 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -3,7 +3,6 @@ from cereal import car from selfdrive.config import Conversions as CV from selfdrive.car.toyota.values import Ecu, CAR, TSS2_CAR, NO_DSU_CAR, MIN_ACC_SPEED, PEDAL_HYST_GAP, CarControllerParams from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint -from selfdrive.swaglog import cloudlog from selfdrive.car.interfaces import CarInterfaceBase EventName = car.CarEvent.EventName @@ -24,6 +23,8 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay ret.steerLimitTimer = 0.4 + ret.stoppingControl = False # Toyota starts braking more when it thinks you want to stop + if candidate not in [CAR.PRIUS, CAR.RAV4, CAR.RAV4H]: # These cars use LQR/INDI ret.lateralTuning.init('pid') ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] @@ -166,36 +167,22 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.17], [0.03]] ret.lateralTuning.pid.kf = 0.00006 - elif candidate == CAR.RAV4_TSS2: + elif candidate in [CAR.RAV4_TSS2, CAR.RAV4H_TSS2]: stop_and_go = True ret.safetyParam = 73 ret.wheelbase = 2.68986 ret.steerRatio = 14.3 tire_stiffness_factor = 0.7933 - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15], [0.05]] - ret.mass = 3370. * CV.LB_TO_KG + STD_CARGO_KG - ret.lateralTuning.pid.kf = 0.00004 + ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] + ret.lateralTuning.pid.kf = 0.00007818594 + # 2019+ Rav4 TSS2 uses two different steering racks and specific tuning seems to be necessary. + # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 for fw in car_fw: - if fw.ecu == "eps" and fw.fwVersion == b"8965B42170\x00\x00\x00\x00\x00\x00": - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] - ret.lateralTuning.pid.kf = 0.00007818594 - break - - elif candidate == CAR.RAV4H_TSS2: - stop_and_go = True - ret.safetyParam = 73 - ret.wheelbase = 2.68986 - ret.steerRatio = 14.3 - tire_stiffness_factor = 0.7933 - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15], [0.05]] - ret.mass = 3800. * CV.LB_TO_KG + STD_CARGO_KG - ret.lateralTuning.pid.kf = 0.00004 - - for fw in car_fw: - if fw.ecu == "eps" and fw.fwVersion == b"8965B42170\x00\x00\x00\x00\x00\x00": - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] - ret.lateralTuning.pid.kf = 0.00007818594 + if fw.ecu == "eps" and fw.fwVersion.startswith(b'\x02'): + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15], [0.05]] + ret.lateralTuning.pid.kf = 0.00004 break elif candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2]: @@ -288,6 +275,16 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] ret.lateralTuning.pid.kf = 0.00006 + elif candidate == CAR.ALPHARD_TSS2: + stop_and_go = True + ret.safetyParam = 73 + ret.wheelbase = 3.00 + ret.steerRatio = 14.2 + tire_stiffness_factor = 0.444 + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.02]] + ret.mass = 4305. * CV.LB_TO_KG + STD_CARGO_KG + ret.lateralTuning.pid.kf = 0.00007818594 + ret.steerRateCost = 1. ret.centerToFront = ret.wheelbase * 0.44 @@ -300,7 +297,6 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - ret.enableCamera = True ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR # Detect smartDSU, which intercepts ACC_CMD from the DSU allowing openpilot to send it smartDsu = 0x2FF in fingerprint[0] @@ -309,9 +305,7 @@ class CarInterface(CarInterfaceBase): ret.enableDsu = (len(found_ecus) > 0) and (Ecu.dsu not in found_ecus) and (candidate not in NO_DSU_CAR) ret.enableGasInterceptor = 0x201 in fingerprint[0] # if the smartDSU is detected, openpilot can send ACC_CMD (and the smartDSU will block it from the DSU) or not (the DSU is "connected") - ret.openpilotLongitudinalControl = ret.enableCamera and (smartDsu or ret.enableDsu or candidate in TSS2_CAR) - cloudlog.warning("ECU DSU Simulated: %r", ret.enableDsu) - cloudlog.warning("ECU Gas Interceptor: %r", ret.enableGasInterceptor) + ret.openpilotLongitudinalControl = smartDsu or ret.enableDsu or candidate in TSS2_CAR # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py index 14bc40744..1bb41f102 100644 --- a/selfdrive/car/toyota/toyotacan.py +++ b/selfdrive/car/toyota/toyotacan.py @@ -28,11 +28,11 @@ def create_lta_steer_command(packer, steer, steer_req, raw_cnt): return packer.make_can_msg("STEERING_LTA", 0, values) -def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead): +def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead, acc_type): # TODO: find the exact canceling bit that does not create a chime values = { "ACCEL_CMD": accel, - "SET_ME_X01": 1, + "ACC_TYPE": acc_type, "DISTANCE": 0, "MINI_CAR": lead, "SET_ME_X3": 3, diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 080b70f61..92f6db919 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -10,8 +10,8 @@ PEDAL_HYST_GAP = 3. * CV.MPH_TO_MS class CarControllerParams: ACCEL_HYST_GAP = 0.02 # don't change accel command for small oscilalitons within this value - ACCEL_MAX = 1.5 # 1.5 m/s2 - ACCEL_MIN = -3.0 # 3 m/s2 + ACCEL_MAX = 1.5 # m/s2 + ACCEL_MIN = -3.0 # m/s2 ACCEL_SCALE = max(ACCEL_MAX, -ACCEL_MIN) STEER_MAX = 1500 @@ -57,27 +57,28 @@ class CAR: LEXUS_NX = "LEXUS NX 2018" LEXUS_NX_TSS2 = "LEXUS NX 2020" MIRAI = "TOYOTA MIRAI 2021" # TSS 2.5 + ALPHARD_TSS2 = "TOYOTA ALPHARD 2020" -# addr: (ecu, cars, bus, 1/freq*100, vl) -STATIC_MSGS = [ - (0x128, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 1, 3, b'\xf4\x01\x90\x83\x00\x37'), - (0x128, Ecu.dsu, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 3, b'\x03\x00\x20\x00\x00\x52'), - (0x141, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 1, 2, b'\x00\x00\x00\x46'), - (0x160, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), - (0x161, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON, CAR.LEXUS_RX), 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), - (0X161, Ecu.dsu, (CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), - (0x283, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), - (0x2E6, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), - (0x2E7, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), - (0x33E, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), - (0x344, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), - (0x365, Ecu.dsu, (CAR.PRIUS, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), - (0x365, Ecu.dsu, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), - (0x366, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), - (0x366, Ecu.dsu, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), - (0x470, Ecu.dsu, (CAR.PRIUS, CAR.LEXUS_RXH), 1, 100, b'\x00\x00\x02\x7a'), - (0x470, Ecu.dsu, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.RAV4H, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 100, b'\x00\x00\x01\x79'), - (0x4CB, Ecu.dsu, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), +# (addr, cars, bus, 1/freq*100, vl) +STATIC_DSU_MSGS = [ + (0x128, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 1, 3, b'\xf4\x01\x90\x83\x00\x37'), + (0x128, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 3, b'\x03\x00\x20\x00\x00\x52'), + (0x141, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 1, 2, b'\x00\x00\x00\x46'), + (0x160, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), + (0x161, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON, CAR.LEXUS_RX), 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), + (0X161, (CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), + (0x283, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), + (0x2E6, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), + (0x2E7, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), + (0x33E, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), + (0x344, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), + (0x365, (CAR.PRIUS, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), + (0x365, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), + (0x366, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), + (0x366, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), + (0x470, (CAR.PRIUS, CAR.LEXUS_RXH), 1, 100, b'\x00\x00\x02\x7a'), + (0x470, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.RAV4H, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 100, b'\x00\x00\x01\x79'), + (0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), ] @@ -119,22 +120,6 @@ FINGERPRINTS = { CAR.COROLLA: [{ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2021: 8, 2022: 8, 2023: 8, 2024: 8 }], - CAR.LEXUS_RXH: [{ - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8 - }, - # RX450HL - # TODO: get proper fingerprint in stock mode - { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 - }, - # RX540H 2019 with color hud - { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1952: 8, 1960: 8, 1990: 8, 1998: 8 - }, - # 2017 RX 450h - { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 744: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1745: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 - }], CAR.CAMRY: [ #XLE and LE { @@ -184,18 +169,6 @@ FINGERPRINTS = { # 2019 Highlander Hybrid Limited Platinum 36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1076: 8, 1077: 8, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], - CAR.AVALON: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 905: 8, 911: 1, 916: 2, 921: 8, 933: 6, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 1005: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1206: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1558: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 - }], - CAR.RAV4_TSS2: [ - # LE - { - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 - }, - # XLE, Limited, and AWD - { - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 - }], CAR.COROLLAH_TSS2: [ # 2019 Taiwan Altis Hybrid { @@ -214,18 +187,6 @@ FINGERPRINTS = { { 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 548: 8, 550: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 764: 8, 767: 4, 800: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 921: 8, 933: 8, 944: 6, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1656: 8, 1664: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 }], - CAR.LEXUS_IS: [ - # IS300 2018 - { - 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 400: 6, 426: 6, 452: 8, 464: 8, 466: 8, 467: 5, 544: 4, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1009: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1184: 8, 1185: 8, 1186: 8, 1187: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1590: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1648: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 - }, - # IS300H 2017 - { - 36: 8, 37: 8, 170: 8, 180: 8, 295: 8, 296: 8, 400: 6, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 7, 921: 7, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1009: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1187: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 - }], - CAR.LEXUS_CTH: [{ - 36: 8, 37: 8, 170: 8, 180: 8, 288: 8, 426: 6, 452: 8, 466: 8, 467: 8, 548: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 800: 8, 810: 2, 832: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 921: 8, 933: 8, 944: 6, 945: 8, 950: 8, 951: 8, 953: 3, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1057: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1116: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1190: 8, 1191: 8, 1192: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1558: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 - }], } @@ -285,15 +246,22 @@ FW_VERSIONS = { CAR.AVALONH_2019: { (Ecu.esp, 0x7b0, None): [ b'F152641040\x00\x00\x00\x00\x00\x00', + b'F152641061\x00\x00\x00\x00\x00\x00', + b'F152641050\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ b'881510704200\x00\x00\x00\x00', + b'881514107100\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B07010\x00\x00\x00\x00\x00\x00', + b'8965B41090\x00\x00\x00\x00\x00\x00', + b'8965B41070\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F4702300\x00\x00\x00\x00', @@ -475,6 +443,7 @@ FW_VERSIONS = { (Ecu.engine, 0x700, None): [ b'\x018966306Q5000\x00\x00\x00\x00', b'\x018966306T3100\x00\x00\x00\x00', + b'\x018966306T4100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 15): [ b'\x018821F6201200\x00\x00\x00\x00', @@ -561,6 +530,7 @@ FW_VERSIONS = { }, CAR.CHRH: { (Ecu.engine, 0x700, None): [ + b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', @@ -569,12 +539,14 @@ FW_VERSIONS = { ], (Ecu.esp, 0x7b0, None): [ b'F152610013\x00\x00\x00\x00\x00\x00', + b'F152610014\x00\x00\x00\x00\x00\x00', b'F152610040\x00\x00\x00\x00\x00\x00', b'F152610190\x00\x00\x00\x00\x00\x00', b'F152610200\x00\x00\x00\x00\x00\x00', b'F152610230\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ + b'8821F0W01000 ', b'8821FF402300 ', b'8821FF402400 ', b'8821FF404000 ', @@ -588,6 +560,7 @@ FW_VERSIONS = { b'8965B10050\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0W01000 ', b'8821FF402300 ', b'8821FF402400 ', b'8821FF404000 ', @@ -659,7 +632,6 @@ FW_VERSIONS = { ], (Ecu.engine, 0x7e0, None): [ b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', @@ -676,7 +648,6 @@ FW_VERSIONS = { b'\x018965B12530\x00\x00\x00\x00\x00\x00', b'\x018965B1255000\x00\x00\x00\x00', b'8965B12361\x00\x00\x00\x00\x00\x00', - b'8965B58040\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'\x01F152602280\x00\x00\x00\x00\x00\x00', @@ -692,7 +663,6 @@ FW_VERSIONS = { b'\x01F152612B90\x00\x00\x00\x00\x00\x00', b'\x01F152612C00\x00\x00\x00\x00\x00\x00', b'F152602191\x00\x00\x00\x00\x00\x00', - b'F152658320\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', @@ -709,7 +679,6 @@ FW_VERSIONS = { b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.COROLLAH_TSS2: { @@ -719,10 +688,12 @@ FW_VERSIONS = { b'\x01896637621000\x00\x00\x00\x00', b'\x01896637624000\x00\x00\x00\x00', b'\x01896637626000\x00\x00\x00\x00', + b'\x01896637648000\x00\x00\x00\x00', b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', @@ -731,6 +702,7 @@ FW_VERSIONS = { b'8965B12361\x00\x00\x00\x00\x00\x00', b'8965B12451\x00\x00\x00\x00\x00\x00', b'8965B76012\x00\x00\x00\x00\x00\x00', + b'8965B76050\x00\x00\x00\x00\x00\x00', b'\x018965B12350\x00\x00\x00\x00\x00\x00', b'\x018965B12470\x00\x00\x00\x00\x00\x00', b'\x018965B12490\x00\x00\x00\x00\x00\x00', @@ -752,6 +724,7 @@ FW_VERSIONS = { b'F152642540\x00\x00\x00\x00\x00\x00', b'F152676293\x00\x00\x00\x00\x00\x00', b'F152676303\x00\x00\x00\x00\x00\x00', + b'F152676304\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', @@ -769,6 +742,7 @@ FW_VERSIONS = { b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.HIGHLANDER: { @@ -1386,6 +1360,7 @@ FW_VERSIONS = { CAR.LEXUS_NX_TSS2: { (Ecu.engine, 0x700, None): [ b'\x018966378B2100\x00\x00\x00\x00', + b'\x018966378G3000\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'\x01F152678221\x00\x00\x00\x00\x00\x00', @@ -1398,6 +1373,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.LEXUS_NXH: { @@ -1405,6 +1381,7 @@ FW_VERSIONS = { b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152678160\x00\x00\x00\x00\x00\x00', @@ -1556,10 +1533,12 @@ FW_VERSIONS = { CAR.LEXUS_RXH_TSS2: { (Ecu.engine, 0x7e0, None): [ b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152648831\x00\x00\x00\x00\x00\x00', + b'F152648D00\x00\x00\x00\x00\x00\x00', b'F152648D60\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -1602,6 +1581,12 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F6201200\x00\x00\x00\x00',], (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',], }, + CAR.ALPHARD_TSS2: { + (Ecu.engine, 0x7e0, None): [b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',], + (Ecu.eps, 0x7a1, None): [b'8965B58040\x00\x00\x00\x00\x00\x00',], + (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F3301400\x00\x00\x00\x00',], + (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',], + }, } STEER_THRESHOLD = 100 @@ -1643,13 +1628,14 @@ DBC = { CAR.LEXUS_NX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.PRIUS_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), CAR.MIRAI: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), + CAR.ALPHARD_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), } # Toyota/Lexus Safety Sense 2.0 and 2.5 TSS2_CAR = set([CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, - CAR.MIRAI, CAR.LEXUS_NX_TSS2]) + CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.ALPHARD_TSS2]) NO_DSU_CAR = TSS2_CAR | set([CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH]) diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 503583f66..d816ba397 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -1,15 +1,16 @@ from cereal import car from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.volkswagen import volkswagencan -from selfdrive.car.volkswagen.values import DBC, CANBUS, MQB_LDW_MESSAGES, BUTTON_STATES, CarControllerParams +from selfdrive.car.volkswagen.values import DBC_FILES, CANBUS, MQB_LDW_MESSAGES, BUTTON_STATES, CarControllerParams as P from opendbc.can.packer import CANPacker +VisualAlert = car.CarControl.HUDControl.VisualAlert class CarController(): def __init__(self, dbc_name, CP, VM): self.apply_steer_last = 0 - self.packer_pt = CANPacker(DBC[CP.carFingerprint]['pt']) + self.packer_pt = CANPacker(DBC_FILES.mqb) self.hcaSameTorqueCount = 0 self.hcaEnabledFrameCount = 0 @@ -23,64 +24,35 @@ class CarController(): def update(self, enabled, CS, frame, actuators, visual_alert, left_lane_visible, right_lane_visible, left_lane_depart, right_lane_depart): """ Controls thread """ - P = CarControllerParams - - # Send CAN commands. can_sends = [] - #-------------------------------------------------------------------------- - # # - # Prepare HCA_01 Heading Control Assist messages with steering torque. # - # # - #-------------------------------------------------------------------------- + # **** Steering Controls ************************************************ # - # The factory camera sends at 50Hz while steering and 1Hz when not. When - # OP is active, Panda filters HCA_01 from the factory camera and OP emits - # HCA_01 at 50Hz. Rate switching creates some confusion in Cabana and - # doesn't seem to add value at this time. The rack will accept HCA_01 at - # 100Hz if we want to control at finer resolution in the future. if frame % P.HCA_STEP == 0: + # Logic to avoid HCA state 4 "refused": + # * Don't steer unless HCA is in state 3 "ready" or 5 "active" + # * Don't steer at standstill + # * Don't send > 3.00 Newton-meters torque + # * Don't send the same torque for > 6 seconds + # * Don't send uninterrupted steering for > 360 seconds + # One frame of HCA disabled is enough to reset the timer, without zeroing the + # torque value. Do that anytime we happen to have 0 torque, or failing that, + # when exceeding ~1/3 the 360 second timer. - # FAULT AVOIDANCE: HCA must not be enabled at standstill. Also stop - # commanding HCA if there's a fault, so the steering rack recovers. if enabled and not (CS.out.standstill or CS.out.steerError or CS.out.steerWarning): - - # FAULT AVOIDANCE: Requested HCA torque must not exceed 3.0 Nm. This - # is inherently handled by scaling to STEER_MAX. The rack doesn't seem - # to care about up/down rate, but we have some evidence it may do its - # own rate limiting, and matching OP helps for accurate tuning. new_steer = int(round(actuators.steer * P.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, P) self.steer_rate_limited = new_steer != apply_steer - - # FAULT AVOIDANCE: HCA must not be enabled for >360 seconds. Sending - # a single frame with HCA disabled is an effective workaround. if apply_steer == 0: - # We can usually reset the timer for free, just by disabling HCA - # when apply_steer is exactly zero, which happens by chance during - # many steer torque direction changes. This could be expanded with - # a small dead-zone to capture all zero crossings, but not seeing a - # major need at this time. hcaEnabled = False self.hcaEnabledFrameCount = 0 else: self.hcaEnabledFrameCount += 1 if self.hcaEnabledFrameCount >= 118 * (100 / P.HCA_STEP): # 118s - # The Kansas I-70 Crosswind Problem: if we truly do need to steer - # in one direction for > 360 seconds, we have to disable HCA for a - # frame while actively steering. Testing shows we can just set the - # disabled flag, and keep sending non-zero torque, which keeps the - # Panda torque rate limiting safety happy. Do so 3x within the 360 - # second window for safety and redundancy. hcaEnabled = False self.hcaEnabledFrameCount = 0 else: hcaEnabled = True - # FAULT AVOIDANCE: HCA torque must not be static for > 6 seconds. - # This is to detect the sending camera being stuck or frozen. OP - # can trip this on a curve if steering is saturated. Avoid this by - # reducing torque 0.01 Nm for one frame. Do so 3x within the 6 - # second period for safety and redundancy. if self.apply_steer_last == apply_steer: self.hcaSameTorqueCount += 1 if self.hcaSameTorqueCount > 1.9 * (100 / P.HCA_STEP): # 1.9s @@ -88,9 +60,7 @@ class CarController(): self.hcaSameTorqueCount = 0 else: self.hcaSameTorqueCount = 0 - else: - # Continue sending HCA_01 messages, with the enable flags turned off. hcaEnabled = False apply_steer = 0 @@ -99,23 +69,14 @@ class CarController(): can_sends.append(volkswagencan.create_mqb_steering_control(self.packer_pt, CANBUS.pt, apply_steer, idx, hcaEnabled)) - #-------------------------------------------------------------------------- - # # - # Prepare LDW_02 HUD messages with lane borders, confidence levels, and # - # the LKAS status LED. # - # # - #-------------------------------------------------------------------------- - - # The factory camera emits this message at 10Hz. When OP is active, Panda - # filters LDW_02 from the factory camera and OP emits LDW_02 at 10Hz. + # **** HUD Controls ***************************************************** # if frame % P.LDW_STEP == 0: - if visual_alert == car.CarControl.HUDControl.VisualAlert.steerRequired: + if visual_alert in [VisualAlert.steerRequired, VisualAlert.ldw]: hud_alert = MQB_LDW_MESSAGES["laneAssistTakeOverSilent"] else: hud_alert = MQB_LDW_MESSAGES["none"] - can_sends.append(volkswagencan.create_mqb_hud_control(self.packer_pt, CANBUS.pt, enabled, CS.out.steeringPressed, hud_alert, left_lane_visible, right_lane_visible, CS.ldw_lane_warning_left, @@ -123,17 +84,9 @@ class CarController(): CS.ldw_dlc, CS.ldw_tlc, CS.out.standstill, left_lane_depart, right_lane_depart)) - #-------------------------------------------------------------------------- - # # - # Prepare GRA_ACC_01 ACC control messages with button press events. # - # # - #-------------------------------------------------------------------------- + # **** ACC Button Controls ********************************************** # - # The car sends this message at 33hz. OP sends it on-demand only for - # virtual button presses. - # - # First create any virtual button press event needed by openpilot, to sync - # stock ACC with OP disengagement, or to auto-resume from stop. + # FIXME: this entire section is in desperate need of refactoring if frame > self.graMsgStartFramePrev + P.GRA_VBP_STEP: if not enabled and CS.out.cruiseState.enabled: @@ -147,31 +100,6 @@ class CarController(): self.graButtonStatesToSend = BUTTON_STATES.copy() self.graButtonStatesToSend["resumeCruise"] = True - # OP/Panda can see this message but can't filter it when integrated at the - # R242 LKAS camera. It could do so if integrated at the J533 gateway, but - # we need a generalized solution that works for either. The message is - # counter-protected, so we need to time our transmissions very precisely - # to achieve fast and fault-free switching between message flows accepted - # at the J428 ACC radar. - # - # Example message flow on the bus, frequency of 33Hz (GRA_ACC_STEP): - # - # CAR: 0 1 2 3 4 5 6 7 8 9 A B C D E F 0 1 2 3 4 5 6 - # EON: 3 4 5 6 7 8 9 A B C D E F 0 1 2 GG^ - # - # If OP needs to send a button press, it waits to see a GRA_ACC_01 message - # counter change, and then immediately follows up with the next increment. - # The OP message will be sent within about 1ms of the car's message, which - # is about 2ms before the car's next message is expected. OP sends for an - # arbitrary duration of 16 messages / ~0.5 sec, in lockstep with each new - # message from the car. - # - # Because OP's counter is synced to the car, J428 immediately accepts the - # OP messages as valid. Further messages from the car get discarded as - # duplicates without a fault. When OP stops sending, the extra time gap - # (GG) to the next valid car message is less than 1 * GRA_ACC_STEP. J428 - # tolerates the gap just fine and control returns to the car immediately. - if CS.graMsgBusCounter != self.graMsgBusCounterPrev: self.graMsgBusCounterPrev = CS.graMsgBusCounter if self.graButtonStatesToSend is not None: diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 833cae6f7..ec3fc53e3 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -4,12 +4,12 @@ from selfdrive.config import Conversions as CV from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser from opendbc.can.can_define import CANDefine -from selfdrive.car.volkswagen.values import DBC, CANBUS, TransmissionType, GearShifter, BUTTON_STATES, CarControllerParams +from selfdrive.car.volkswagen.values import DBC_FILES, CANBUS, TransmissionType, GearShifter, BUTTON_STATES, CarControllerParams class CarState(CarStateBase): def __init__(self, CP): super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + can_define = CANDefine(DBC_FILES.mqb) if CP.transmissionType == TransmissionType.automatic: self.shifter_values = can_define.dv["Getriebe_11"]["GE_Fahrstufe"] elif CP.transmissionType == TransmissionType.direct: @@ -133,8 +133,8 @@ class CarState(CarStateBase): self.buttonStates["setCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Tip_Setzen"]) self.buttonStates["resumeCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Tip_Wiederaufnahme"]) self.buttonStates["gapAdjustCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Verstellung_Zeitluecke"]) - ret.leftBlinker = bool(pt_cp.vl["Gateway_72"]["BH_Blinker_li"]) - ret.rightBlinker = bool(pt_cp.vl["Gateway_72"]["BH_Blinker_re"]) + ret.leftBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Left"]) + ret.rightBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Right"]) # Read ACC hardware button type configuration info that has to pass thru # to the radar. Ends up being different for steering wheel buttons vs @@ -173,8 +173,8 @@ class CarState(CarStateBase): ("ZV_HFS_offen", "Gateway_72", 0), # Door open, rear left ("ZV_HBFS_offen", "Gateway_72", 0), # Door open, rear right ("ZV_HD_offen", "Gateway_72", 0), # Trunk or hatch open - ("BH_Blinker_li", "Gateway_72", 0), # Left turn signal on - ("BH_Blinker_re", "Gateway_72", 0), # Right turn signal on + ("Comfort_Signal_Left", "Blinkmodi_02", 0), # Left turn signal including comfort blink interval + ("Comfort_Signal_Right", "Blinkmodi_02", 0), # Right turn signal including comfort blink interval ("AB_Gurtschloss_FA", "Airbag_02", 0), # Seatbelt status, driver ("AB_Gurtschloss_BF", "Airbag_02", 0), # Seatbelt status, passenger ("ESP_Fahrer_bremst", "ESP_05", 0), # Brake pedal pressed @@ -216,6 +216,7 @@ class CarState(CarStateBase): ("Motor_14", 10), # From J623 Engine control module ("Airbag_02", 5), # From J234 Airbag control module ("Kombi_01", 2), # From J285 Instrument cluster + ("Blinkmodi_02", 1), # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) ("Einheiten_01", 1), # From J??? not known if gateway, cluster, or BCM ] @@ -238,7 +239,7 @@ class CarState(CarStateBase): signals += MqbExtraSignals.bsm_radar_signals checks += MqbExtraSignals.bsm_radar_checks - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.pt) + return CANParser(DBC_FILES.mqb, signals, checks, CANBUS.pt) @staticmethod def get_cam_can_parser(CP): @@ -257,7 +258,7 @@ class CarState(CarStateBase): ("LDW_02", 10) # From R242 Driver assistance camera ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.cam) + return CANParser(DBC_FILES.mqb, signals, checks, CANBUS.cam) class MqbExtraSignals: # Additional signal and message lists for optional or bus-portable controllers diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 55401af0f..1735a8dc7 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -1,5 +1,4 @@ from cereal import car -from selfdrive.swaglog import cloudlog from selfdrive.car.volkswagen.values import CAR, BUTTON_STATES, TransmissionType, GearShifter from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint from selfdrive.car.interfaces import CarInterfaceBase @@ -41,7 +40,6 @@ class CarInterface(CarInterfaceBase): else: # No trans message at all, must be a true stick-shift manual ret.transmissionType = TransmissionType.manual - cloudlog.info("Detected transmission type: %s", ret.transmissionType) # Global tuning defaults, can be overridden per-vehicle @@ -82,6 +80,11 @@ class CarInterface(CarInterfaceBase): ret.mass = 1715 + STD_CARGO_KG ret.wheelbase = 2.74 + elif candidate == CAR.TOURAN_MK2: + # Average of SWB and LWB variants + ret.mass = 1516 + STD_CARGO_KG + ret.wheelbase = 2.79 + elif candidate == CAR.AUDI_A3_MK3: # Averages of all 8V A3 variants ret.mass = 1335 + STD_CARGO_KG @@ -124,7 +127,6 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.45 - ret.enableCamera = True ret.enableBsm = 0x30F in fingerprint[0] # TODO: get actual value, for now starting with reasonable value for diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index fcbf56ac1..3bad8fc3e 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -1,7 +1,10 @@ # flake8: noqa -from selfdrive.car import dbc_dict +from collections import defaultdict +from typing import Dict + from cereal import car +from selfdrive.car import dbc_dict Ecu = car.CarParams.Ecu class CarControllerParams: @@ -26,6 +29,11 @@ class CANBUS: pt = 0 cam = 2 +class DBC_FILES: + mqb = "vw_mqb_2010" # Used for all cars with MQB-style CAN messaging + +DBC = defaultdict(lambda: dbc_dict(DBC_FILES.mqb, None)) # type: Dict[str, Dict[str, str]] + TransmissionType = car.CarParams.TransmissionType GearShifter = car.CarState.GearShifter @@ -61,6 +69,7 @@ class CAR: JETTA_MK7 = "VOLKSWAGEN JETTA 7TH GEN" # Chassis BU, Mk7 Jetta PASSAT_MK8 = "VOLKSWAGEN PASSAT 8TH GEN" # Chassis 3G, Mk8 Passat and variants TIGUAN_MK2 = "VOLKSWAGEN TIGUAN 2ND GEN" # Chassis AD/BW, Mk2 VW Tiguan and variants + TOURAN_MK2 = "VOLKSWAGEN TOURAN 2ND GEN" # Chassis 1T, Mk2 VW Touran and variants AUDI_A3_MK3 = "AUDI A3 3RD GEN" # Chassis 8V/FF, Mk3 Audi A3 and variants AUDI_Q2_MK1 = "AUDI Q2 1ST GEN" # Chassis GA, Mk1 Audi Q2 (RoW) and Q2L (China only) SEAT_ATECA_MK1 = "SEAT ATECA 1ST GEN" # Chassis 5F, Mk1 SEAT Ateca and CUPRA Ateca @@ -70,12 +79,22 @@ class CAR: SKODA_SUPERB_MK3 = "SKODA SUPERB 3RD GEN" # Chassis 3V/NP, Mk3 Skoda Superb and variants SKODA_OCTAVIA_MK3 = "SKODA OCTAVIA 3RD GEN" # Chassis NE, Mk3 Skoda Octavia and variants +# All supported cars should return FW from the engine, srs, eps, and fwdRadar. Cars +# with a manual trans won't return transmission firmware, but all other cars will. +# +# The 0xF187 SW part number query should return in the form of N[NX][NX] NNN NNN [X[X]], +# where N=number, X=letter, and the trailing two letters are optional. Performance +# tuners sometimes tamper with that field (e.g. 8V0 9C0 BB0 1 from COBB/EQT). Tampered +# ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have +# them repaired by the tuner before including them in openpilot. + FW_VERSIONS = { CAR.ATLAS_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8703H906026AA\xf1\x899970', b'\xf1\x8703H906026F \xf1\x896696', b'\xf1\x8703H906026F \xf1\x899970', + b'\xf1\x8703H906026S \xf1\x896693', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158A \xf1\x893387', @@ -84,6 +103,7 @@ FW_VERSIONS = { (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\0161914151912001103111122031200', b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\0162214152212001105141122052900', + b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\0162214152212001105141122052900', ], (Ecu.eps, 0x712, None): [ b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\00571B60924A1', @@ -104,6 +124,7 @@ FW_VERSIONS = { b'\xf1\x8704E906024K \xf1\x896811', b'\xf1\x8704E906027GR\xf1\x892394', b'\xf1\x8704E906027MA\xf1\x894958', + b'\xf1\x8704L906026BP\xf1\x897608', b'\xf1\x8704L906026NF\xf1\x899528', b'\xf1\x8704L906056CR\xf1\x895813', b'\xf1\x8704L906056HE\xf1\x893758', @@ -123,6 +144,7 @@ FW_VERSIONS = { b'\xf1\x878V0906264F \xf1\x890003', b'\xf1\x878V0906264L \xf1\x890002', b'\xf1\x878V0906264M \xf1\x890001', + b'\xf1\x878V09C0BB01 \xf1\x890001', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927749AP\xf1\x892943', @@ -134,9 +156,11 @@ FW_VERSIONS = { b'\xf1\x870CW300048J \xf1\x890611', b'\xf1\x870D9300012 \xf1\x894913', b'\xf1\x870D9300012 \xf1\x894937', + b'\xf1\x870D9300012 \xf1\x895045', b'\xf1\x870D9300014M \xf1\x895004', b'\xf1\x870D9300020S \xf1\x895201', b'\xf1\x870D9300040S \xf1\x894311', + b'\xf1\x870D9300041H \xf1\x895220', b'\xf1\x870DD300045K \xf1\x891120', b'\xf1\x870DD300046F \xf1\x891601', b'\xf1\x870GC300012A \xf1\x891403', @@ -155,6 +179,7 @@ FW_VERSIONS = { b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\0211413001113120053114317121C111C9113', b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\02314160011123300314211012230229333463100', b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\023141600111233003142405A2252229333463100', + b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\0211413001113120006110417121A101A9113', b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\023271112111312--071104171825102591131211', b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\023271212111312--071104171838103891131211', b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\023341512112212--071104172328102891131211', @@ -171,6 +196,7 @@ FW_VERSIONS = { b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\00561A01612A0', b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\00566A0J612A1', b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\00566A00514A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\00566A0J712A1', b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\00571A0J714A1', b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\00571A01A18A1', @@ -183,13 +209,15 @@ FW_VERSIONS = { b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\00522A00402A0', b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00511A00403A0', b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\00516A00604A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\00516A00604A1', b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\00516A07A02A1', b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521A20B03A1', b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\00521A00442A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\00571A01A16A1', b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\00571A01A18A1', b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\00521A00442A1', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\00101', @@ -267,21 +295,47 @@ FW_VERSIONS = { }, CAR.TIGUAN_MK2: { (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906026EJ\xf1\x893661', + b'\xf1\x8704L906027G \xf1\x899893', b'\xf1\x8783A907115B \xf1\x890005', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158DT\xf1\x893698', + b'\xf1\x870DL300011N \xf1\x892001', + b'\xf1\x870DL300013A \xf1\x893005', ], (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\02331310031333334313132573732379333313100', b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02316143231313500314641011750179333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02331310031333336313140013950399333423100', ], (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\00571A60634A1', b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A60804A1', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572J \xf1\x890156', b'\xf1\x872Q0907572R \xf1\x890372', ], }, + CAR.TOURAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906026HM\xf1\x893017', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041E \xf1\x891005', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\023363500213533353141324C4732479333313100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x873Q0907572C \xf1\x890195', + ], + }, CAR.AUDI_A3_MK3: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906023AN\xf1\x893695', @@ -412,21 +466,26 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906027HD\xf1\x893742', b'\xf1\x8704L906021DT\xf1\x898127', + b'\xf1\x8704L906026BS\xf1\x891541', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870D9300041J \xf1\x894902', b'\xf1\x870D9300041P \xf1\x894507', ], (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', ], (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\00566A01513A1', b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\00101', b'\xf1\x875Q0907572P \xf1\x890682', ], }, @@ -474,19 +533,3 @@ FW_VERSIONS = { ], }, } - -DBC = { - CAR.ATLAS_MK1: dbc_dict('vw_mqb_2010', None), - CAR.GOLF_MK7: dbc_dict('vw_mqb_2010', None), - CAR.JETTA_MK7: dbc_dict('vw_mqb_2010', None), - CAR.PASSAT_MK8: dbc_dict('vw_mqb_2010', None), - CAR.TIGUAN_MK2: dbc_dict('vw_mqb_2010', None), - CAR.AUDI_A3_MK3: dbc_dict('vw_mqb_2010', None), - CAR.AUDI_Q2_MK1: dbc_dict('vw_mqb_2010', None), - CAR.SEAT_ATECA_MK1: dbc_dict('vw_mqb_2010', None), - CAR.SEAT_LEON_MK3: dbc_dict('vw_mqb_2010', None), - CAR.SKODA_KODIAQ_MK1: dbc_dict('vw_mqb_2010', None), - CAR.SKODA_OCTAVIA_MK3: dbc_dict('vw_mqb_2010', None), - CAR.SKODA_SCALA_MK1: dbc_dict('vw_mqb_2010', None), - CAR.SKODA_SUPERB_MK3: dbc_dict('vw_mqb_2010', None), -} diff --git a/selfdrive/clocksd/clocksd.cc b/selfdrive/clocksd/clocksd.cc index c6ad4061a..951a92467 100644 --- a/selfdrive/clocksd/clocksd.cc +++ b/selfdrive/clocksd/clocksd.cc @@ -1,9 +1,10 @@ -#include -#include #include #include #include +#include +#include + // Apple doesn't have timerfd #ifdef __APPLE__ #include @@ -52,7 +53,7 @@ int main() { if (err < 0) break; #else // Just run at 1Hz on apple - while (!do_exit){ + while (!do_exit) { util::sleep_for(1000); #endif diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript index 8f6c1dc18..57c789479 100644 --- a/selfdrive/common/SConscript +++ b/selfdrive/common/SConscript @@ -35,3 +35,6 @@ else: _gpucommon = fxn('gpucommon', files, LIBS=_gpu_libs) Export('_common', '_gpucommon', '_gpu_libs') + +if GetOption('test'): + env.Program('tests/test_util', ['tests/test_util.cc'], LIBS=[_common]) diff --git a/selfdrive/common/clutil.cc b/selfdrive/common/clutil.cc index 526c66b22..68207c286 100644 --- a/selfdrive/common/clutil.cc +++ b/selfdrive/common/clutil.cc @@ -1,10 +1,9 @@ #include "selfdrive/common/clutil.h" -#include -#include -#include #include +#include +#include #include #include #include diff --git a/selfdrive/common/clutil.h b/selfdrive/common/clutil.h index 71523c273..4c8723d64 100644 --- a/selfdrive/common/clutil.h +++ b/selfdrive/common/clutil.h @@ -1,8 +1,7 @@ #pragma once -#include -#include -#include +#include +#include #ifdef __APPLE__ #include diff --git a/selfdrive/common/glutil.cc b/selfdrive/common/glutil.cc index 7e53975e1..f13e132a8 100644 --- a/selfdrive/common/glutil.cc +++ b/selfdrive/common/glutil.cc @@ -1,9 +1,8 @@ #include "selfdrive/common/glutil.h" -#include -#include -#include - +#include +#include +#include #include static GLuint load_shader(GLenum shaderType, const char *src) { diff --git a/selfdrive/common/gpio.cc b/selfdrive/common/gpio.cc index 8a2885316..033d6da4f 100644 --- a/selfdrive/common/gpio.cc +++ b/selfdrive/common/gpio.cc @@ -1,30 +1,31 @@ #include "selfdrive/common/gpio.h" #include -#include #include +#include + #include "selfdrive/common/util.h" // We assume that all pins have already been exported on boot, // and that we have permission to write to them. -int gpio_init(int pin_nr, bool output){ +int gpio_init(int pin_nr, bool output) { char pin_dir_path[50]; int pin_dir_path_len = snprintf(pin_dir_path, sizeof(pin_dir_path), "/sys/class/gpio/gpio%d/direction", pin_nr); - if(pin_dir_path_len <= 0){ + if(pin_dir_path_len <= 0) { return -1; } const char *value = output ? "out" : "in"; return util::write_file(pin_dir_path, (void*)value, strlen(value)); } -int gpio_set(int pin_nr, bool high){ +int gpio_set(int pin_nr, bool high) { char pin_val_path[50]; int pin_val_path_len = snprintf(pin_val_path, sizeof(pin_val_path), "/sys/class/gpio/gpio%d/value", pin_nr); - if(pin_val_path_len <= 0){ + if(pin_val_path_len <= 0) { return -1; } return util::write_file(pin_val_path, (void*)(high ? "1" : "0"), 1); diff --git a/selfdrive/common/i2c.cc b/selfdrive/common/i2c.cc index c2842948b..80738be80 100644 --- a/selfdrive/common/i2c.cc +++ b/selfdrive/common/i2c.cc @@ -1,11 +1,11 @@ #include "selfdrive/common/i2c.h" #include -#include #include #include #include +#include #include #include "selfdrive/common/swaglog.h" @@ -19,21 +19,21 @@ extern "C" { #include } -I2CBus::I2CBus(uint8_t bus_id){ +I2CBus::I2CBus(uint8_t bus_id) { char bus_name[20]; snprintf(bus_name, 20, "/dev/i2c-%d", bus_id); i2c_fd = open(bus_name, O_RDWR); - if(i2c_fd < 0){ + if(i2c_fd < 0) { throw std::runtime_error("Failed to open I2C bus"); } } -I2CBus::~I2CBus(){ - if(i2c_fd >= 0){ close(i2c_fd); } +I2CBus::~I2CBus() { + if(i2c_fd >= 0) { close(i2c_fd); } } -int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len){ +int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len) { int ret = 0; ret = ioctl(i2c_fd, I2C_SLAVE, device_address); @@ -46,7 +46,7 @@ fail: return ret; } -int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data){ +int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data) { int ret = 0; ret = ioctl(i2c_fd, I2C_SLAVE, device_address); @@ -61,14 +61,14 @@ fail: #else -I2CBus::I2CBus(uint8_t bus_id){ +I2CBus::I2CBus(uint8_t bus_id) { UNUSED(bus_id); i2c_fd = -1; } -I2CBus::~I2CBus(){} +I2CBus::~I2CBus() {} -int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len){ +int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len) { UNUSED(device_address); UNUSED(register_address); UNUSED(buffer); @@ -76,7 +76,7 @@ int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t return -1; } -int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data){ +int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data) { UNUSED(device_address); UNUSED(register_address); UNUSED(data); diff --git a/selfdrive/common/i2c.h b/selfdrive/common/i2c.h index d5788510d..0669116bb 100644 --- a/selfdrive/common/i2c.h +++ b/selfdrive/common/i2c.h @@ -1,6 +1,7 @@ #pragma once -#include +#include + #include class I2CBus { diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h index 83aff9705..4eb306805 100644 --- a/selfdrive/common/modeldata.h +++ b/selfdrive/common/modeldata.h @@ -1,5 +1,7 @@ #pragma once const int TRAJECTORY_SIZE = 33; +const int LON_MPC_N = 32; +const int LAT_MPC_N = 16; const float MIN_DRAW_DISTANCE = 10.0; const float MAX_DRAW_DISTANCE = 100.0; diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index 45eac661b..a14076513 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -5,14 +5,14 @@ #endif // _GNU_SOURCE #include -#include -#include -#include #include #include #include #include +#include +#include +#include #include #include @@ -42,9 +42,9 @@ void params_sig_handler(int signal) { params_do_exit = 1; } -int fsync_dir(const char* path){ +int fsync_dir(const char* path) { int fd = HANDLE_EINTR(open(path, O_RDONLY, 0755)); - if (fd < 0){ + if (fd < 0) { return -1; } @@ -78,7 +78,7 @@ int mkdir_p(std::string path) { return 0; } -bool ensure_params_path(const std::string ¶m_path, const std::string &key_path) { +static bool create_params_path(const std::string ¶m_path, const std::string &key_path) { // Make sure params path exists if (!util::file_exists(param_path) && mkdir_p(param_path) != 0) { return false; @@ -117,6 +117,12 @@ bool ensure_params_path(const std::string ¶m_path, const std::string &key_pa return chmod(key_path.c_str(), 0777) == 0; } +static void ensure_params_path(const std::string ¶ms_path) { + if (!create_params_path(params_path, params_path + "/d")) { + throw std::runtime_error(util::string_format("Failed to ensure params path, errno=%d", errno)); + } +} + class FileLock { public: FileLock(const std::string& file_name, int op) : fn_(file_name), op_(op) {} @@ -128,7 +134,6 @@ class FileLock { return; } if (HANDLE_EINTR(flock(fd_, op_)) < 0) { - close(fd_); LOGE("Failed to lock file %s, errno=%d", fn_.c_str(), errno); } } @@ -145,6 +150,7 @@ std::unordered_map keys = { {"ApiCache_DriveStats", PERSISTENT}, {"ApiCache_Device", PERSISTENT}, {"ApiCache_Owner", PERSISTENT}, + {"ApiCache_NavDestinations", PERSISTENT}, {"AthenadPid", PERSISTENT}, {"CalibrationParams", PERSISTENT}, {"CarBatteryCapacity", PERSISTENT}, @@ -153,7 +159,8 @@ std::unordered_map keys = { {"CarVin", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION_ON}, {"CommunityFeaturesToggle", PERSISTENT}, {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION_ON}, - {"EnableLteOnroad", PERSISTENT}, + {"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, + {"DisableRadar", PERSISTENT}, // WARNING: THIS DISABLES AEB {"EndToEndToggle", PERSISTENT}, {"CompletedTrainingVersion", PERSISTENT}, {"DisablePowerDown", PERSISTENT}, @@ -186,6 +193,7 @@ std::unordered_map keys = { {"LiveParameters", PERSISTENT}, {"MapboxToken", PERSISTENT}, {"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, + {"NavSettingTime24h", PERSISTENT}, {"OpenpilotEnabledToggle", PERSISTENT}, {"PandaFirmware", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT}, {"PandaFirmwareHex", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT}, @@ -217,15 +225,19 @@ std::unordered_map keys = { {"Offroad_UnofficialHardware", CLEAR_ON_MANAGER_START}, {"Offroad_NvmeMissing", CLEAR_ON_MANAGER_START}, {"ForcePowerDown", CLEAR_ON_MANAGER_START}, + {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, }; } // namespace Params::Params(bool persistent_param) : Params(persistent_param ? persistent_params_path : default_params_path) {} +std::once_flag default_params_path_ensured; Params::Params(const std::string &path) : params_path(path) { - if (!ensure_params_path(params_path, params_path + "/d")) { - throw std::runtime_error(util::string_format("Failed to ensure params path, errno=%d", errno)); + if (path == default_params_path) { + std::call_once(default_params_path_ensured, ensure_params_path, path); + } else { + ensure_params_path(path); } } @@ -268,7 +280,7 @@ int Params::put(const char* key, const char* value, size_t value_size) { // fsync parent directory path = params_path + "/d"; result = fsync_dir(path.c_str()); - } while(0); + } while (false); close(tmp_fd); remove(tmp_path.c_str()); diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h index 3d59f07b1..bc1372295 100644 --- a/selfdrive/common/params.h +++ b/selfdrive/common/params.h @@ -1,7 +1,5 @@ #pragma once -#include - #include #include #include diff --git a/selfdrive/common/swaglog.cc b/selfdrive/common/swaglog.cc index 80d2379d9..74488e220 100644 --- a/selfdrive/common/swaglog.cc +++ b/selfdrive/common/swaglog.cc @@ -2,10 +2,10 @@ #define _GNU_SOURCE #endif -#include "swaglog.h" +#include "selfdrive/common/swaglog.h" -#include -#include +#include +#include #include #include diff --git a/selfdrive/common/timing.h b/selfdrive/common/timing.h index b940cc924..83f55e0c4 100644 --- a/selfdrive/common/timing.h +++ b/selfdrive/common/timing.h @@ -1,7 +1,7 @@ #pragma once -#include -#include +#include +#include #ifdef __APPLE__ #define CLOCK_BOOTTIME CLOCK_MONOTONIC diff --git a/selfdrive/common/util.cc b/selfdrive/common/util.cc index c629550c8..78f9e409f 100644 --- a/selfdrive/common/util.cc +++ b/selfdrive/common/util.cc @@ -1,8 +1,7 @@ #include "selfdrive/common/util.h" -#include - #include +#include #include #include #include @@ -55,29 +54,29 @@ int set_core_affinity(int core) { namespace util { std::string read_file(const std::string& fn) { - std::ifstream ifs(fn, std::ios::binary | std::ios::ate); - if (ifs) { - std::ifstream::pos_type pos = ifs.tellg(); - if (pos != std::ios::beg) { - std::string result; - result.resize(pos); - ifs.seekg(0, std::ios::beg); - ifs.read(result.data(), pos); - if (ifs) { + std::ifstream f(fn, std::ios::binary | std::ios::in); + if (f.is_open()) { + f.seekg(0, std::ios::end); + int size = f.tellg(); + if (f.good() && size > 0) { + std::string result(size, '\0'); + f.seekg(0, std::ios::beg); + f.read(result.data(), size); + // return either good() or has reached end-of-file (e.g. /sys/power/wakeup_count) + if (f.good() || f.eof()) { + result.resize(f.gcount()); return result; } } + // fallback for files created on read, e.g. procfs + std::stringstream buffer; + buffer << f.rdbuf(); + return buffer.str(); } - ifs.close(); - - // fallback for files created on read, e.g. procfs - std::ifstream f(fn); - std::stringstream buffer; - buffer << f.rdbuf(); - return buffer.str(); + return std::string(); } -int read_files_in_dir(std::string path, std::map *contents) { +int read_files_in_dir(const std::string &path, std::map *contents) { DIR *d = opendir(path.c_str()); if (!d) return -1; @@ -119,7 +118,7 @@ bool file_exists(const std::string& fn) { std::string getenv_default(const char* env_var, const char * suffix, const char* default_val) { const char* env_val = getenv(env_var); - if (env_val != NULL){ + if (env_val != NULL) { return std::string(env_val) + std::string(suffix); } else { return std::string(default_val); @@ -156,7 +155,11 @@ std::string dir_name(std::string const &path) { return path.substr(0, pos); } -struct tm get_time(){ +bool is_valid_dongle_id(std::string const& dongle_id) { + return !dongle_id.empty() && dongle_id != "UnregisteredDevice"; +} + +struct tm get_time() { time_t rawtime; time(&rawtime); @@ -166,10 +169,10 @@ struct tm get_time(){ return sys_time; } -bool time_valid(struct tm sys_time){ +bool time_valid(struct tm sys_time) { int year = 1900 + sys_time.tm_year; int month = 1 + sys_time.tm_mon; - return (year > 2020) || (year == 2020 && month >= 10); + return (year > 2021) || (year == 2021 && month >= 6); } } // namespace util diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index 698ca819b..460fb8f5c 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -58,10 +58,11 @@ std::string tohex(const uint8_t* buf, size_t buf_size); std::string hexdump(const std::string& in); std::string base_name(std::string const& path); std::string dir_name(std::string const& path); +bool is_valid_dongle_id(std::string const& dongle_id); // **** file fhelpers ***** std::string read_file(const std::string& fn); -int read_files_in_dir(std::string path, std::map* contents); +int read_files_in_dir(const std::string& path, std::map* contents); int write_file(const char* path, const void* data, size_t size, int flags = O_WRONLY, mode_t mode = 0777); std::string readlink(const std::string& path); bool file_exists(const std::string& fn); @@ -126,6 +127,7 @@ public: return x_; } inline void reset(float x) { x_ = x; } + inline float x(){ return x_; } private: float x_, k_; diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index 5518dbc16..45bf96517 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.5-d4ab1f1e2-2021-06-07T22:13:55" +#define COMMA_VERSION "0.8.6" diff --git a/selfdrive/common/visionimg.h b/selfdrive/common/visionimg.h index cf3b36b79..e8917f3bd 100644 --- a/selfdrive/common/visionimg.h +++ b/selfdrive/common/visionimg.h @@ -1,6 +1,6 @@ #pragma once -#include "visionbuf.h" +#include "cereal/visionipc/visionbuf.h" #ifdef __APPLE__ #include diff --git a/selfdrive/common/watchdog.cc b/selfdrive/common/watchdog.cc index fe95e23fd..33307f720 100644 --- a/selfdrive/common/watchdog.cc +++ b/selfdrive/common/watchdog.cc @@ -10,7 +10,7 @@ const std::string watchdog_fn_prefix = "/dev/shm/wd_"; // + -bool watchdog_kick(){ +bool watchdog_kick() { std::string fn = watchdog_fn_prefix + std::to_string(getpid()); std::string cur_t = std::to_string(nanos_since_boot()); diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 6608ce3c2..344d1b15a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -13,6 +13,7 @@ from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can from selfdrive.controls.lib.lane_planner import CAMERA_OFFSET from selfdrive.controls.lib.drive_helpers import update_v_cruise, initialize_v_cruise +from selfdrive.controls.lib.drive_helpers import get_lag_adjusted_curvature from selfdrive.controls.lib.longcontrol import LongControl, STARTING_TARGET_SPEED from selfdrive.controls.lib.latcontrol_pid import LatControlPID from selfdrive.controls.lib.latcontrol_indi import LatControlINDI @@ -21,7 +22,6 @@ from selfdrive.controls.lib.latcontrol_angle import LatControlAngle from selfdrive.controls.lib.events import Events, ET from selfdrive.controls.lib.alertmanager import AlertManager from selfdrive.controls.lib.vehicle_model import VehicleModel -from selfdrive.controls.lib.longitudinal_planner import LON_MPC_STEP from selfdrive.locationd.calibrationd import Calibration from selfdrive.hardware import HARDWARE, TICI @@ -57,12 +57,16 @@ class Controls: if TICI: self.camera_packets.append("wideRoadCameraState") + params = Params() + self.joystick_mode = params.get_bool("JoystickDebugMode") + joystick_packet = ['testJoystick'] if self.joystick_mode else [] + self.sm = sm if self.sm is None: ignore = ['driverCameraState', 'managerState'] if SIMULATION else None self.sm = messaging.SubMaster(['deviceState', 'pandaState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', - 'managerState', 'liveParameters', 'radarState'] + self.camera_packets, + 'managerState', 'liveParameters', 'radarState'] + self.camera_packets + joystick_packet, ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan']) self.can_sock = can_sock @@ -80,10 +84,8 @@ class Controls: self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan']) # read params - params = Params() self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") - self.enable_lte_onroad = params.get_bool("EnableLteOnroad") community_feature_toggle = params.get_bool("CommunityFeaturesToggle") openpilot_enabled_toggle = params.get_bool("OpenpilotEnabledToggle") passive = params.get_bool("Passive") or not openpilot_enabled_toggle @@ -93,9 +95,8 @@ class Controls: car_recognized = self.CP.carName != 'mock' - # If stock camera is disconnected, we loaded car controls and it's not dashcam mode - controller_available = self.CP.enableCamera and self.CI.CC is not None and not passive and not self.CP.dashcamOnly - community_feature = self.CP.communityFeature or self.CP.fuzzyFingerprint or \ + controller_available = self.CI.CC is not None and not passive and not self.CP.dashcamOnly + community_feature = self.CP.communityFeature or \ self.CP.fingerprintSource == car.CarParams.FingerprintSource.can community_feature_disallowed = community_feature and (not community_feature_toggle) self.read_only = not car_recognized or not controller_available or \ @@ -141,6 +142,8 @@ class Controls: self.events_prev = [] self.current_alert_types = [ET.PERMANENT] self.logged_comm_issue = False + self.v_target = 0.0 + self.a_target = 0.0 # TODO: no longer necessary, aside from process replay self.sm['liveParameters'].valid = True @@ -150,12 +153,15 @@ class Controls: if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) - if community_feature_disallowed and car_recognized: + if community_feature_disallowed and car_recognized and not self.CP.dashcamOnly: self.events.add(EventName.communityFeatureDisallowed, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) elif self.read_only: self.events.add(EventName.dashcamMode, static=True) + elif self.joystick_mode: + self.events.add(EventName.joystickDebug, static=True) + self.startup_event = None # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) @@ -184,11 +190,11 @@ class Controls: self.events.add(EventName.lowBattery) if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) - if self.sm['deviceState'].freeSpacePercent < 7: + if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) # TODO: make tici threshold the same - if self.sm['deviceState'].memoryUsagePercent > (90 if TICI else 65): + if self.sm['deviceState'].memoryUsagePercent > (90 if TICI else 65) and not SIMULATION: self.events.add(EventName.lowMemory) # Alert if fan isn't spinning for 5 seconds @@ -239,7 +245,9 @@ class Controls: elif not self.sm.all_alive_and_valid(): self.events.add(EventName.commIssue) if not self.logged_comm_issue: - cloudlog.error(f"commIssue - valid: {self.sm.valid} - alive: {self.sm.alive}") + invalid = [s for s, valid in self.sm.valid.items() if not valid] + not_alive = [s for s, alive in self.sm.alive.items() if not alive] + cloudlog.event("commIssue", invalid=invalid, not_alive=not_alive) self.logged_comm_issue = True else: self.logged_comm_issue = False @@ -258,7 +266,7 @@ class Controls: if self.sm['longitudinalPlan'].fcw or (self.enabled and self.sm['modelV2'].meta.hardBrakePredicted): self.events.add(EventName.fcw) - if TICI and self.enable_lte_onroad: + if TICI: logs = messaging.drain_sock(self.log_sock, wait_for_one=False) messages = [] for m in logs: @@ -281,8 +289,7 @@ class Controls: # TODO: fix simulator if not SIMULATION: if not NOSENSOR: - if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000) and \ - (not TICI or self.enable_lte_onroad): + if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000): # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes self.events.add(EventName.noGps) if not self.sm.all_alive(self.camera_packets): @@ -298,7 +305,12 @@ class Controls: self.events.add(EventName.processNotRunning) # Only allow engagement with brake pressed when stopped behind another stopped car - if CS.brakePressed and self.sm['longitudinalPlan'].vTargetFuture >= STARTING_TARGET_SPEED \ + speeds = self.sm['longitudinalPlan'].speeds + if len(speeds) > 1: + v_future = speeds[-1] + else: + v_future = 100.0 + if CS.brakePressed and v_future >= STARTING_TARGET_SPEED \ and self.CP.openpilotLongitudinalControl and CS.vEgo < 0.3: self.events.add(EventName.noTarget) @@ -313,6 +325,7 @@ class Controls: all_valid = CS.canValid and self.sm.all_alive_and_valid() if not self.initialized and (all_valid or self.sm.frame * DT_CTRL > 2.0): + self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) self.initialized = True Params().put_bool("ControlsReady", True) @@ -343,9 +356,9 @@ class Controls: self.v_cruise_kph_last = self.v_cruise_kph # if stock cruise is completely disabled, then we can use our own set speed logic - if not self.CP.enableCruise: + if not self.CP.pcmCruise: self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.buttonEvents, self.enabled) - elif self.CP.enableCruise and CS.cruiseState.enabled: + elif self.CP.pcmCruise and CS.cruiseState.enabled: self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH # decrease the soft disable timer at every step, as it's reset on @@ -437,18 +450,31 @@ class Controls: self.LaC.reset() self.LoC.reset(v_pid=CS.vEgo) - long_plan_age = DT_CTRL * (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) - # no greater than dt mpc + dt, to prevent too high extraps - dt = min(long_plan_age, LON_MPC_STEP + DT_CTRL) + DT_CTRL + if not self.joystick_mode: + # Gas/Brake PID loop + actuators.gas, actuators.brake, self.v_target, self.a_target = self.LoC.update(self.active, CS, self.CP, long_plan) - a_acc_sol = long_plan.aStart + (dt / LON_MPC_STEP) * (long_plan.aTarget - long_plan.aStart) - v_acc_sol = long_plan.vStart + dt * (a_acc_sol + long_plan.aStart) / 2.0 + # Steering PID loop and lateral MPC + desired_curvature, desired_curvature_rate = get_lag_adjusted_curvature(self.CP, CS.vEgo, + lat_plan.psis, + lat_plan.curvatures, + lat_plan.curvatureRates) + actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(self.active, CS, self.CP, self.VM, params, + desired_curvature, desired_curvature_rate) + else: + lac_log = log.ControlsState.LateralDebugState.new_message() + if self.sm.rcv_frame['testJoystick'] > 0 and self.active: + gb = clip(self.sm['testJoystick'].axes[0], -1, 1) + actuators.gas, actuators.brake = max(gb, 0), max(-gb, 0) - # Gas/Brake PID loop - actuators.gas, actuators.brake = self.LoC.update(self.active, CS, v_acc_sol, long_plan.vTargetFuture, a_acc_sol, self.CP) + steer = clip(self.sm['testJoystick'].axes[1], -1, 1) + # max angle is 45 for angle-based cars + actuators.steer, actuators.steeringAngleDeg = steer, steer * 45. - # Steering PID loop and lateral MPC - actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(self.active, CS, self.CP, self.VM, params, lat_plan) + lac_log.active = True + lac_log.steeringAngleDeg = CS.steeringAngleDeg + lac_log.output = steer + lac_log.saturated = abs(steer) >= 0.9 # Check for difference between desired angle and angle for angle based control angle_control_saturated = self.CP.steerControlType == car.CarParams.SteerControlType.angle and \ @@ -471,9 +497,9 @@ class Controls: if left_deviation or right_deviation: self.events.add(EventName.steerSaturated) - return actuators, v_acc_sol, a_acc_sol, lac_log + return actuators, lac_log - def publish_logs(self, CS, start_time, actuators, v_acc, a_acc, lac_log): + def publish_logs(self, CS, start_time, actuators, lac_log): """Send actuators and hud commands to the car, send controlsstate and MPC logging""" CC = car.CarControl.new_message() @@ -481,14 +507,18 @@ class Controls: CC.actuators = actuators CC.cruiseControl.override = True - CC.cruiseControl.cancel = not self.CP.enableCruise or (not self.enabled and CS.cruiseState.enabled) + CC.cruiseControl.cancel = not self.CP.pcmCruise or (not self.enabled and CS.cruiseState.enabled) + if self.joystick_mode and self.sm.rcv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: + CC.cruiseControl.cancel = True + # TODO remove car specific stuff in controls # Some override values for Honda # brake discount removes a sharp nonlinearity brake_discount = (1.0 - clip(actuators.brake * 3., 0.0, 1.0)) speed_override = max(0.0, (self.LoC.v_pid + CS.cruiseState.speedOffset) * brake_discount) - CC.cruiseControl.speedOverride = float(speed_override if self.CP.enableCruise else 0.0) - CC.cruiseControl.accelOverride = self.CI.calc_accel_override(CS.aEgo, self.sm['longitudinalPlan'].aTarget, CS.vEgo, self.sm['longitudinalPlan'].vTarget) + CC.cruiseControl.speedOverride = float(speed_override if self.CP.pcmCruise else 0.0) + CC.cruiseControl.accelOverride = float(self.CI.calc_accel_override(CS.aEgo, self.a_target, + CS.vEgo, self.v_target)) CC.hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) CC.hudControl.speedVisible = self.enabled @@ -533,12 +563,8 @@ class Controls: # Curvature & Steering angle params = self.sm['liveParameters'] - lat_plan = self.sm['lateralPlan'] - steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetAverageDeg) curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo) - angle_steers_des = math.degrees(self.VM.get_steer_from_curvature(-lat_plan.curvature, CS.vEgo)) - angle_steers_des += params.angleOffsetDeg # controlsState dat = messaging.new_message('controlsState') @@ -557,7 +583,6 @@ class Controls: controlsState.enabled = self.enabled controlsState.active = self.active controlsState.curvature = curvature - controlsState.steeringAngleDesiredDeg = angle_steers_des controlsState.state = self.state controlsState.engageable = not self.events.any(ET.NO_ENTRY) controlsState.longControlState = self.LoC.long_control_state @@ -566,14 +591,14 @@ class Controls: controlsState.upAccelCmd = float(self.LoC.pid.p) controlsState.uiAccelCmd = float(self.LoC.pid.i) controlsState.ufAccelCmd = float(self.LoC.pid.f) - controlsState.vTargetLead = float(v_acc) - controlsState.aTarget = float(a_acc) controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) controlsState.canErrorCounter = self.can_error_counter - if self.CP.steerControlType == car.CarParams.SteerControlType.angle: + if self.joystick_mode: + controlsState.lateralControlState.debugState = lac_log + elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: controlsState.lateralControlState.angleState = lac_log elif self.CP.lateralTuning.which() == 'pid': controlsState.lateralControlState.pidState = lac_log @@ -629,12 +654,12 @@ class Controls: self.prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) - actuators, v_acc, a_acc, lac_log = self.state_control(CS) + actuators, lac_log = self.state_control(CS) self.prof.checkpoint("State Control") # Publish data - self.publish_logs(CS, start_time, actuators, v_acc, a_acc, lac_log) + self.publish_logs(CS, start_time, actuators, lac_log) self.prof.checkpoint("Sent") def controlsd_thread(self): diff --git a/selfdrive/controls/lib/cluster/fastcluster.cpp b/selfdrive/controls/lib/cluster/fastcluster.cpp index 6b0af725c..d2b557d6f 100644 --- a/selfdrive/controls/lib/cluster/fastcluster.cpp +++ b/selfdrive/controls/lib/cluster/fastcluster.cpp @@ -188,11 +188,11 @@ extern "C" { // 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++){ + 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 ++){ + for (int k = 0; k < m; k ++) { double error = pts[i * m + k] - pts[j * m + k]; d += (error * error); } diff --git a/selfdrive/controls/lib/cluster/test.cpp b/selfdrive/controls/lib/cluster/test.cpp index 208867775..d4e4fa536 100644 --- a/selfdrive/controls/lib/cluster/test.cpp +++ b/selfdrive/controls/lib/cluster/test.cpp @@ -5,7 +5,7 @@ extern "C" { } -int main(int argc, const char* argv[]){ +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, @@ -25,7 +25,7 @@ int main(int argc, const char* argv[]){ cluster_points_centroid(n, m, pts, 2.5 * 2.5, idx); - for (int i = 0; i < n; i++){ + for (int i = 0; i < n; i++) { assert(idx[i] == correct_idx[i]); } diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index ba433066d..9f554c88b 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,15 +1,24 @@ -from common.numpy_fast import clip, interp -from selfdrive.config import Conversions as CV from cereal import car +from common.numpy_fast import clip, interp +from common.realtime import DT_MDL +from selfdrive.config import Conversions as CV +from selfdrive.modeld.constants import T_IDXS + # kph V_CRUISE_MAX = 135 V_CRUISE_MIN = 8 V_CRUISE_DELTA = 8 V_CRUISE_ENABLE_MIN = 40 -MPC_N = 16 +LAT_MPC_N = 16 +LON_MPC_N = 32 +CONTROL_N = 17 CAR_ROTATION_RADIUS = 0.0 +# this corresponds to 80deg/s and 20deg/s steering angle in a toyota corolla +MAX_CURVATURE_RATES = [0.03762194918267951, 0.003441203371932992] +MAX_CURVATURE_RATE_SPEEDS = [0, 35] + class MPC_COST_LAT: PATH = 1.0 HEADING = 1.0 @@ -52,3 +61,31 @@ def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last): return v_cruise_last return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX))) + + +def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): + if len(psis) != CONTROL_N: + psis = [0.0 for i in range(CONTROL_N)] + curvatures = [0.0 for i in range(CONTROL_N)] + curvature_rates = [0.0 for i in range(CONTROL_N)] + + # TODO this needs more thought, use .2s extra for now to estimate other delays + delay = CP.steerActuatorDelay + .2 + current_curvature = curvatures[0] + psi = interp(delay, T_IDXS[:CONTROL_N], psis) + desired_curvature_rate = curvature_rates[0] + + # MPC can plan to turn the wheel and turn back before t_delay. This means + # in high delay cases some corrections never even get commanded. So just use + # psi to calculate a simple linearization of desired curvature + curvature_diff_from_psi = psi / (max(v_ego, 1e-1) * delay) - current_curvature + desired_curvature = current_curvature + 2 * curvature_diff_from_psi + + max_curvature_rate = interp(v_ego, MAX_CURVATURE_RATE_SPEEDS, MAX_CURVATURE_RATES) + safe_desired_curvature_rate = clip(desired_curvature_rate, + -max_curvature_rate, + max_curvature_rate) + safe_desired_curvature = clip(desired_curvature, + current_curvature - max_curvature_rate/DT_MDL, + current_curvature + max_curvature_rate/DT_MDL) + return safe_desired_curvature, safe_desired_curvature_rate diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 62e9dab76..ef150709a 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -13,6 +13,7 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert AudibleAlert = car.CarControl.HUDControl.AudibleAlert EventName = car.CarEvent.EventName + # Alert priorities class Priority(IntEnum): LOWEST = 0 @@ -22,6 +23,7 @@ class Priority(IntEnum): HIGH = 4 HIGHEST = 5 + # Event types class ET: ENABLE = 'enable' @@ -33,6 +35,7 @@ class ET: IMMEDIATE_DISABLE = 'immediateDisable' PERMANENT = 'permanent' + # get event name from enum EVENT_NAME = {v: k for k, v in EventName.schema.enumerants.items()} @@ -56,7 +59,7 @@ class Events: self.events.append(event_name) def clear(self): - self.events_prev = {k: (v+1 if k in self.events else 0) for k, v in self.events_prev.items()} + 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): @@ -94,10 +97,11 @@ class Events: event = car.CarEvent.new_message() event.name = event_name for event_type in EVENTS.get(event_name, {}).keys(): - setattr(event, event_type , True) + setattr(event, event_type, True) ret.append(event) return ret + class Alert: def __init__(self, alert_text_1: str, @@ -138,6 +142,7 @@ class Alert: def __gt__(self, alert2) -> bool: return self.alert_priority > alert2.alert_priority + class NoEntryAlert(Alert): def __init__(self, alert_text_2, audible_alert=AudibleAlert.chimeError, visual_alert=VisualAlert.none, duration_hud_alert=2.): @@ -161,6 +166,7 @@ class ImmediateDisableAlert(Alert): Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 2.2, 3., 4.), + class EngagementAlert(Alert): def __init__(self, audible_alert=True): super().__init__("", "", @@ -168,14 +174,15 @@ class EngagementAlert(Alert): Priority.MID, VisualAlert.none, audible_alert, .2, 0., 0.), + class NormalPermanentAlert(Alert): def __init__(self, alert_text_1: str, alert_text_2: str, duration_text: float = 0.2): super().__init__(alert_text_1, alert_text_2, AlertStatus.normal, AlertSize.mid if len(alert_text_2) else AlertSize.small, Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., duration_text), -# ********** alert callback functions ********** +# ********** alert callback functions ********** def below_steer_speed_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: speed = int(round(CP.minSteerSpeed * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH))) unit = "km/h" if metric else "mph" @@ -183,7 +190,8 @@ def below_steer_speed_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: "TAKE CONTROL", "Steer Unavailable Below %d %s" % (speed, unit), AlertStatus.userPrompt, AlertSize.mid, - Priority.MID, VisualAlert.steerRequired, AudibleAlert.none, 0., 0.4, .3) + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimePrompt, 0., 0.4, .3) + def calibration_incomplete_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: speed = int(MIN_SPEED_FILTER * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH)) @@ -194,6 +202,7 @@ def calibration_incomplete_alert(CP: car.CarParams, sm: messaging.SubMaster, met AlertStatus.normal, AlertSize.mid, Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2) + def no_gps_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: gps_integrated = sm['pandaState'].pandaType in [log.PandaState.PandaType.uno, log.PandaState.PandaType.dos] return Alert( @@ -202,12 +211,14 @@ def no_gps_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Al AlertStatus.normal, AlertSize.mid, Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2, creation_delay=300.) + def wrong_car_mode_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: text = "Cruise Mode Disabled" if CP.carName == "honda": text = "Main Switch Off" return NoEntryAlert(text, duration_hud_alert=0.) + def startup_fuzzy_fingerprint_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: return Alert( "WARNING: No Exact Match on Car Model", @@ -215,17 +226,29 @@ def startup_fuzzy_fingerprint_alert(CP: car.CarParams, sm: messaging.SubMaster, AlertStatus.userPrompt, AlertSize.mid, Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.) + +def joystick_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> Alert: + axes = sm['testJoystick'].axes + gb, steer = list(axes)[:2] if len(axes) else (0., 0.) + return Alert( + "Joystick Mode", + f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .1) + + EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, bool], Alert]]]] = { # ********** events with no alerts ********** # ********** events only containing alerts displayed in all states ********** EventName.joystickDebug: { + ET.WARNING: joystick_alert, ET.PERMANENT: Alert( - "DEBUG ALERT", + "Joystick Mode", "", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, VisualAlert.none, AudibleAlert.none, .1, .1, .1), + AlertStatus.normal, AlertSize.small, + Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 0.1), }, EventName.controlsInitializing: { @@ -248,6 +271,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), }, + # Car is recognized, but marked as dashcam only EventName.startupNoControl: { ET.PERMANENT: Alert( "Dashcam mode", @@ -256,6 +280,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), }, + # Car is not recognized EventName.startupNoCar: { ET.PERMANENT: Alert( "Dashcam mode for unsupported car", @@ -264,6 +289,14 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), }, + # openpilot uses the version strings from various ECUs to detect the correct car model. + # Usually all ECUs are recognized and an exact match to a car model can be made. Sometimes + # one or two ECUs have unrecognized versions, but the others are present in the database. + # If openpilot is confident about the match to a car model, it fingerprints anyway. + # In this case an alert is thrown since there is a small chance the wrong car was detected + # and the user should pay extra attention. + # This alert can be prevented by adding all ECU firmware version to openpilot: + # https://github.com/commaai/openpilot/wiki/Fingerprinting EventName.startupFuzzyFingerprint: { ET.PERMANENT: startup_fuzzy_fingerprint_alert, }, @@ -292,6 +325,9 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOWER, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, + # Some features or cars are marked as community features. If openpilot + # detects the use of a community feature it switches to dashcam mode + # until these features are allowed using a toggle in settings. EventName.communityFeatureDisallowed: { # LOW priority to overcome Cruise Error ET.PERMANENT: Alert( @@ -301,6 +337,9 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), }, + # openpilot doesn't recognize the car. This switches openpilot into a + # read-only mode. This can be solved by adding your fingerprint. + # See https://github.com/commaai/openpilot/wiki/Fingerprinting for more information EventName.carUnrecognized: { ET.PERMANENT: Alert( "Dashcam Mode", @@ -340,7 +379,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo "TAKE CONTROL", "Lane Departure Detected", AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimePrompt, 1., 2., 3.), + Priority.LOW, VisualAlert.ldw, AudibleAlert.chimePrompt, 1., 2., 3.), }, # ********** events only containing alerts that display while engaged ********** @@ -353,6 +392,14 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .0, .0, .1, creation_delay=1.), }, + # openpilot tries to learn certain parameters about your car by observing + # how the car behaves to steering inputs from both human and openpilot driving. + # This includes: + # - steer ratio: gear ratio of the steering rack. Steering angle divided by tire angle + # - tire stiffness: how much grip your tires have + # - angle offset: most steering angle sensors are offset and measure a non zero angle when driving straight + # This alert is thrown when any of these values exceed a sanity check. This can be caused by + # bad alignment or bad sensor data. If this happens consistently consider creating an issue on GitHub EventName.vehicleModelInvalid: { ET.NO_ENTRY: NoEntryAlert("Vehicle Parameter Identification Failed"), ET.SOFT_DISABLE: SoftDisableAlert("Vehicle Parameter Identification Failed"), @@ -363,7 +410,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOWEST, VisualAlert.steerRequired, AudibleAlert.none, .0, .0, .1), }, - EventName.steerTempUnavailableUserOverride: { + EventName.steerTempUnavailableSilent: { ET.WARNING: Alert( "Steering Temporarily Unavailable", "", @@ -419,14 +466,6 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), }, - EventName.driverMonitorLowAcc: { - ET.WARNING: Alert( - "CHECK DRIVER FACE VISIBILITY", - "Driver Monitoring Uncertain", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .4, 0., 1.5), - }, - EventName.manualRestart: { ET.WARNING: Alert( "TAKE CONTROL", @@ -487,18 +526,24 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimePrompt, 1., 1., 1.), }, + # Thrown when the fan is driven at >50% but is not rotating EventName.fanMalfunction: { ET.PERMANENT: NormalPermanentAlert("Fan Malfunction", "Contact Support"), }, + # Camera is not outputting frames at a constant framerate EventName.cameraMalfunction: { ET.PERMANENT: NormalPermanentAlert("Camera Malfunction", "Contact Support"), }, + # Unused EventName.gpsMalfunction: { ET.PERMANENT: NormalPermanentAlert("GPS Malfunction", "Contact Support"), }, + # When the GPS position and localizer diverge the localizer is reset to the + # current GPS position. This alert is thrown when the localizer is reset + # more often than expected. EventName.localizerMalfunction: { ET.PERMANENT: NormalPermanentAlert("Localizer unstable", "Contact Support"), }, @@ -604,6 +649,11 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo ET.NO_ENTRY: NoEntryAlert("Gear not D"), }, + # This alert is thrown when the calibration angles are outside of the acceptable range. + # For example if the device is pointed too much to the left or the right. + # Usually this can only be solved by removing the mount from the windshield completely, + # and attaching while making sure the device is pointed straight forward and is level. + # See https://comma.ai/setup for more information EventName.calibrationInvalid: { ET.PERMANENT: NormalPermanentAlert("Calibration Invalid", "Remount Device and Recalibrate"), ET.SOFT_DISABLE: SoftDisableAlert("Calibration Invalid: Remount Device & Recalibrate"), @@ -636,12 +686,17 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo ET.NO_ENTRY: NoEntryAlert("Low Battery"), }, + # Different openpilot services communicate between each other at a certain + # interval. If communication does not follow the regular schedule this alert + # is thrown. This can mean a service crashed, did not broadcast a message for + # ten times the regular interval, or the average interval is more than 10% too high. EventName.commIssue: { ET.SOFT_DISABLE: SoftDisableAlert("Communication Issue between Processes"), ET.NO_ENTRY: NoEntryAlert("Communication Issue between Processes", audible_alert=AudibleAlert.chimeDisengage), }, + # Thrown when manager detects a service exited unexpectedly while driving EventName.processNotRunning: { ET.NO_ENTRY: NoEntryAlert("System Malfunction: Reboot Your Device", audible_alert=AudibleAlert.chimeDisengage), @@ -649,19 +704,29 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo EventName.radarFault: { ET.SOFT_DISABLE: SoftDisableAlert("Radar Error: Restart the Car"), - ET.NO_ENTRY : NoEntryAlert("Radar Error: Restart the Car"), + ET.NO_ENTRY: NoEntryAlert("Radar Error: Restart the Car"), }, + # Every frame from the camera should be processed by the model. If modeld + # is not processing frames fast enough they have to be dropped. This alert is + # thrown when over 20% of frames are dropped. EventName.modeldLagging: { ET.SOFT_DISABLE: SoftDisableAlert("Driving model lagging"), - ET.NO_ENTRY : NoEntryAlert("Driving model lagging"), + ET.NO_ENTRY: NoEntryAlert("Driving model lagging"), }, + # Besides predicting the path, lane lines and lead car data the model also + # predicts the current velocity and rotation speed of the car. If the model is + # very uncertain about the current velocity while the car is moving, this + # usually means the model has trouble understanding the scene. This is used + # as a heuristic to warn the driver. EventName.posenetInvalid: { ET.SOFT_DISABLE: SoftDisableAlert("Model Output Uncertain"), ET.NO_ENTRY: NoEntryAlert("Model Output Uncertain"), }, + # When the localizer detects an acceleration of more than 40 m/s^2 (~4G) we + # alert the driver the device might have fallen from the windshield. EventName.deviceFalling: { ET.SOFT_DISABLE: SoftDisableAlert("Device Fell Off Mount"), ET.NO_ENTRY: NoEntryAlert("Device Fell Off Mount"), @@ -670,7 +735,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo EventName.lowMemory: { ET.SOFT_DISABLE: SoftDisableAlert("Low Memory: Reboot Your Device"), ET.PERMANENT: NormalPermanentAlert("Low Memory", "Reboot your Device"), - ET.NO_ENTRY : NoEntryAlert("Low Memory: Reboot Your Device", + ET.NO_ENTRY: NoEntryAlert("Low Memory: Reboot Your Device", audible_alert=AudibleAlert.chimeDisengage), }, @@ -699,12 +764,18 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo duration_text=10.), }, + # Sometimes the USB stack on the device can get into a bad state + # causing the connection to the panda to be lost EventName.usbError: { ET.SOFT_DISABLE: SoftDisableAlert("USB Error: Reboot Your Device"), ET.PERMANENT: NormalPermanentAlert("USB Error: Reboot Your Device", ""), ET.NO_ENTRY: NoEntryAlert("USB Error: Reboot Your Device"), }, + # This alert can be thrown for the following reasons: + # - No CAN data received at all + # - CAN data is received, but some message are not received at the right frequency + # If you're not writing a new car port, this is usually cause by faulty wiring EventName.canError: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("CAN Error: Check Connections"), ET.PERMANENT: Alert( @@ -745,15 +816,24 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo ET.NO_ENTRY: NoEntryAlert("Reverse Gear"), }, + # On cars that use stock ACC the car can decide to cancel ACC for various reasons. + # When this happens we can no long control the car so the user needs to be warned immediately. EventName.cruiseDisabled: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Cruise Is Off"), }, + # For planning the trajectory Model Predictive Control (MPC) is used. This is + # an optimization algorithm that is not guaranteed to find a feasible solution. + # If no solution is found or the solution has a very high cost this alert is thrown. EventName.plannerError: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Planner Solution Error"), ET.NO_ENTRY: NoEntryAlert("Planner Solution Error"), }, + # When the relay in the harness box opens the CAN bus between the LKAS camera + # and the rest of the car is separated. When messages from the LKAS camera + # are received on the car side this usually means the relay hasn't opened correctly + # and this alert is thrown. EventName.relayMalfunction: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Harness Malfunction"), ET.PERMANENT: NormalPermanentAlert("Harness Malfunction", "Check Hardware"), @@ -766,7 +846,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo "No close lead car", AlertStatus.normal, AlertSize.mid, Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), - ET.NO_ENTRY : NoEntryAlert("No Close Lead Car"), + ET.NO_ENTRY: NoEntryAlert("No Close Lead Car"), }, EventName.speedTooLow: { @@ -777,12 +857,13 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), }, + # When the car is driving faster than most cars in the training data the model outputs can be unpredictable EventName.speedTooHigh: { ET.WARNING: Alert( "Speed Too High", "Model uncertain at this speed", - AlertStatus.normal, AlertSize.mid, - Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 2.2, 3., 4.), + AlertStatus.userPrompt, AlertSize.mid, + Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarning2Repeat, 2.2, 3., 4.), ET.NO_ENTRY: Alert( "Speed Too High", "Slow down to engage", diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py index eab023b98..a641687b4 100644 --- a/selfdrive/controls/lib/latcontrol_angle.py +++ b/selfdrive/controls/lib/latcontrol_angle.py @@ -9,7 +9,7 @@ class LatControlAngle(): def reset(self): pass - def update(self, active, CS, CP, VM, params, lat_plan): + def update(self, active, CS, CP, VM, params, desired_curvature, desired_curvature_rate): angle_log = log.ControlsState.LateralAngleState.new_message() if CS.vEgo < 0.3 or not active: @@ -17,7 +17,7 @@ class LatControlAngle(): angle_steers_des = float(CS.steeringAngleDeg) else: angle_log.active = True - angle_steers_des = math.degrees(VM.get_steer_from_curvature(-lat_plan.curvature, CS.vEgo)) + angle_steers_des = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo)) angle_steers_des += params.angleOffsetDeg angle_log.saturated = False diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py index ba3987895..6f234efde 100644 --- a/selfdrive/controls/lib/latcontrol_indi.py +++ b/selfdrive/controls/lib/latcontrol_indi.py @@ -80,7 +80,7 @@ class LatControlINDI(): return self.sat_count > self.sat_limit - def update(self, active, CS, CP, VM, params, lat_plan): + def update(self, active, CS, CP, VM, params, curvature, curvature_rate): self.speed = CS.vEgo # Update Kalman filter y = np.array([[math.radians(CS.steeringAngleDeg)], [math.radians(CS.steeringRateDeg)]]) @@ -91,15 +91,15 @@ class LatControlINDI(): indi_log.steeringRateDeg = math.degrees(self.x[1]) indi_log.steeringAccelDeg = math.degrees(self.x[2]) + steers_des = VM.get_steer_from_curvature(-curvature, CS.vEgo) + steers_des += math.radians(params.angleOffsetDeg) if CS.vEgo < 0.3 or not active: indi_log.active = False self.output_steer = 0.0 self.delayed_output = 0.0 else: - steers_des = VM.get_steer_from_curvature(-lat_plan.curvature, CS.vEgo) - steers_des += math.radians(params.angleOffsetDeg) - rate_des = VM.get_steer_from_curvature(-lat_plan.curvatureRate, CS.vEgo) + rate_des = VM.get_steer_from_curvature(-curvature_rate, CS.vEgo) # Expected actuator value alpha = 1. - DT_CTRL / (self.RC + DT_CTRL) @@ -142,4 +142,4 @@ class LatControlINDI(): check_saturation = (CS.vEgo > 10.) and not CS.steeringRateLimited and not CS.steeringPressed indi_log.saturated = self._check_saturation(self.output_steer, check_saturation, steers_max) - return float(self.output_steer), 0, indi_log + return float(self.output_steer), float(steers_des), indi_log diff --git a/selfdrive/controls/lib/latcontrol_lqr.py b/selfdrive/controls/lib/latcontrol_lqr.py index 03464ea52..e445fb3f8 100644 --- a/selfdrive/controls/lib/latcontrol_lqr.py +++ b/selfdrive/controls/lib/latcontrol_lqr.py @@ -1,10 +1,10 @@ import math import numpy as np -from selfdrive.controls.lib.drive_helpers import get_steer_max from common.numpy_fast import clip from common.realtime import DT_CTRL from cereal import log +from selfdrive.controls.lib.drive_helpers import get_steer_max class LatControlLQR(): @@ -44,7 +44,7 @@ class LatControlLQR(): return self.sat_count > self.sat_limit - def update(self, active, CS, CP, VM, params, lat_plan): + def update(self, active, CS, CP, VM, params, desired_curvature, desired_curvature_rate): lqr_log = log.ControlsState.LateralLQRState.new_message() steers_max = get_steer_max(CP, CS.vEgo) @@ -53,7 +53,7 @@ class LatControlLQR(): # Subtract offset. Zero angle should correspond to zero torque steering_angle_no_offset = CS.steeringAngleDeg - params.angleOffsetAverageDeg - desired_angle = math.degrees(VM.get_steer_from_curvature(-lat_plan.curvature, CS.vEgo)) + desired_angle = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo)) instant_offset = params.angleOffsetDeg - params.angleOffsetAverageDeg desired_angle += instant_offset # Only add offset that originates from vehicle model errors @@ -98,4 +98,4 @@ class LatControlLQR(): lqr_log.output = output_steer lqr_log.lqrOutput = lqr_output lqr_log.saturated = saturated - return output_steer, 0, lqr_log + return output_steer, desired_angle, lqr_log diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index 65f2c6fbf..b258f9ede 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -15,12 +15,12 @@ class LatControlPID(): def reset(self): self.pid.reset() - def update(self, active, CS, CP, VM, params, lat_plan): + def update(self, active, CS, CP, VM, params, desired_curvature, desired_curvature_rate): pid_log = log.ControlsState.LateralPIDState.new_message() pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg) - angle_steers_des_no_offset = math.degrees(VM.get_steer_from_curvature(-lat_plan.curvature, CS.vEgo)) + angle_steers_des_no_offset = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo)) angle_steers_des = angle_steers_des_no_offset + params.angleOffsetDeg if CS.vEgo < 0.3 or not active: @@ -48,4 +48,4 @@ class LatControlPID(): pid_log.output = output_steer pid_log.saturated = bool(self.pid.saturated) - return output_steer, 0, pid_log + return output_steer, angle_steers_des, pid_log diff --git a/selfdrive/controls/lib/lateral_mpc/SConscript b/selfdrive/controls/lib/lateral_mpc/SConscript index 15dbeb19b..4812369e0 100644 --- a/selfdrive/controls/lib/lateral_mpc/SConscript +++ b/selfdrive/controls/lib/lateral_mpc/SConscript @@ -1,27 +1,28 @@ Import('env', 'arch') cpp_path = [ - "#selfdrive", - "#phonelibs/acado/include", - "#phonelibs/acado/include/acado", - "#phonelibs/qpoases/INCLUDE", - "#phonelibs/qpoases/INCLUDE/EXTRAS", - "#phonelibs/qpoases/SRC/", - "#phonelibs/qpoases", - "lib_mpc_export", + "#", + "#selfdrive", + "#phonelibs/acado/include", + "#phonelibs/acado/include/acado", + "#phonelibs/qpoases/INCLUDE", + "#phonelibs/qpoases/INCLUDE/EXTRAS", + "#phonelibs/qpoases/SRC/", + "#phonelibs/qpoases", + "lib_mpc_export", ] generated_c = [ - 'lib_mpc_export/acado_auxiliary_functions.c', - 'lib_mpc_export/acado_qpoases_interface.cpp', - 'lib_mpc_export/acado_integrator.c', - 'lib_mpc_export/acado_solver.c', + 'lib_mpc_export/acado_auxiliary_functions.c', + 'lib_mpc_export/acado_qpoases_interface.cpp', + 'lib_mpc_export/acado_integrator.c', + 'lib_mpc_export/acado_solver.c', ] generated_h = [ - 'lib_mpc_export/acado_common.h', - 'lib_mpc_export/acado_auxiliary_functions.h', - 'lib_mpc_export/acado_qpoases_interface.hpp', + 'lib_mpc_export/acado_common.h', + 'lib_mpc_export/acado_auxiliary_functions.h', + 'lib_mpc_export/acado_qpoases_interface.hpp', ] interface_dir = Dir('lib_mpc_export') diff --git a/selfdrive/controls/lib/lateral_mpc/generator.cpp b/selfdrive/controls/lib/lateral_mpc/generator.cpp index 171e7231c..61a0f5c70 100644 --- a/selfdrive/controls/lib/lateral_mpc/generator.cpp +++ b/selfdrive/controls/lib/lateral_mpc/generator.cpp @@ -4,7 +4,6 @@ #define deg2rad(d) (d/180.0*M_PI) -const int N_steps = 16; using namespace std; int main( ) @@ -26,8 +25,11 @@ int main( ) // Equations of motion - f << dot(xx) == v_ego * cos(psi) - rotation_radius * sin(psi) * (v_ego * curvature); - f << dot(yy) == v_ego * sin(psi) + rotation_radius * cos(psi) * (v_ego * curvature); + f << dot(xx) == v_ego * cos(psi); + f << dot(yy) == v_ego * sin(psi); + // disable rotation radius for now + //f << dot(xx) == v_ego * cos(psi) - rotation_radius * sin(psi) * (v_ego * curvature); + //f << dot(yy) == v_ego * sin(psi) + rotation_radius * cos(psi) * (v_ego * curvature); f << dot(psi) == v_ego * curvature; f << dot(curvature) == curvature_rate; @@ -65,9 +67,9 @@ int main( ) // QN(2,2) = 1.0; // QN(3,3) = 1.0; - double T_IDXS_ARR[N_steps + 1]; - memcpy(T_IDXS_ARR, T_IDXS, (N_steps + 1) * sizeof(double)); - Grid times(N_steps + 1, T_IDXS_ARR); + double T_IDXS_ARR[LAT_MPC_N + 1]; + memcpy(T_IDXS_ARR, T_IDXS, (LAT_MPC_N + 1) * sizeof(double)); + Grid times(LAT_MPC_N + 1, T_IDXS_ARR); OCP ocp(times); ocp.subjectTo(f); @@ -84,8 +86,8 @@ int main( ) mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); mpc.set( INTEGRATOR_TYPE, INT_RK4 ); - mpc.set( NUM_INTEGRATOR_STEPS, 2500); - mpc.set( MAX_NUM_QP_ITERATIONS, 1000); + mpc.set( NUM_INTEGRATOR_STEPS, 1000); + mpc.set( MAX_NUM_QP_ITERATIONS, 50); mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h index 41638459f..4e48894de 100644 --- a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h @@ -155,8 +155,8 @@ real_t x0[ 4 ]; */ typedef struct ACADOworkspace_ { -/** Column vector of size: 28 */ -real_t rhs_aux[ 28 ]; +/** Column vector of size: 14 */ +real_t rhs_aux[ 14 ]; real_t rk_ttt; diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c index 71231b37e..df3b7133e 100644 --- a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c @@ -25,52 +25,38 @@ void acado_rhs_forw(const real_t* in, real_t* out) const real_t* xd = in; const real_t* u = in + 24; const real_t* od = in + 25; -/* Vector of auxiliary variables; number of elements: 28. */ +/* Vector of auxiliary variables; number of elements: 14. */ real_t* a = acadoWorkspace.rhs_aux; /* Compute intermediate quantities: */ a[0] = (cos(xd[2])); a[1] = (sin(xd[2])); -a[2] = (sin(xd[2])); -a[3] = (cos(xd[2])); -a[4] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2]))); -a[5] = (xd[12]*a[4]); -a[6] = (cos(xd[2])); -a[7] = (xd[12]*a[6]); -a[8] = (xd[13]*a[4]); -a[9] = (xd[13]*a[6]); -a[10] = (xd[14]*a[4]); -a[11] = (xd[14]*a[6]); -a[12] = (xd[15]*a[4]); -a[13] = (xd[15]*a[6]); -a[14] = (cos(xd[2])); -a[15] = (xd[12]*a[14]); -a[16] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2]))); -a[17] = (xd[12]*a[16]); -a[18] = (xd[13]*a[14]); -a[19] = (xd[13]*a[16]); -a[20] = (xd[14]*a[14]); -a[21] = (xd[14]*a[16]); -a[22] = (xd[15]*a[14]); -a[23] = (xd[15]*a[16]); -a[24] = (xd[22]*a[4]); -a[25] = (xd[22]*a[6]); -a[26] = (xd[22]*a[14]); -a[27] = (xd[22]*a[16]); +a[2] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2]))); +a[3] = (xd[12]*a[2]); +a[4] = (xd[13]*a[2]); +a[5] = (xd[14]*a[2]); +a[6] = (xd[15]*a[2]); +a[7] = (cos(xd[2])); +a[8] = (xd[12]*a[7]); +a[9] = (xd[13]*a[7]); +a[10] = (xd[14]*a[7]); +a[11] = (xd[15]*a[7]); +a[12] = (xd[22]*a[2]); +a[13] = (xd[22]*a[7]); /* Compute outputs: */ -out[0] = ((od[0]*a[0])-((od[1]*a[1])*(od[0]*xd[3]))); -out[1] = ((od[0]*a[2])+((od[1]*a[3])*(od[0]*xd[3]))); +out[0] = (od[0]*a[0]); +out[1] = (od[0]*a[1]); out[2] = (od[0]*xd[3]); out[3] = u[0]; -out[4] = ((od[0]*a[5])-(((od[1]*a[7])*(od[0]*xd[3]))+((od[1]*a[1])*(od[0]*xd[16])))); -out[5] = ((od[0]*a[8])-(((od[1]*a[9])*(od[0]*xd[3]))+((od[1]*a[1])*(od[0]*xd[17])))); -out[6] = ((od[0]*a[10])-(((od[1]*a[11])*(od[0]*xd[3]))+((od[1]*a[1])*(od[0]*xd[18])))); -out[7] = ((od[0]*a[12])-(((od[1]*a[13])*(od[0]*xd[3]))+((od[1]*a[1])*(od[0]*xd[19])))); -out[8] = ((od[0]*a[15])+(((od[1]*a[17])*(od[0]*xd[3]))+((od[1]*a[3])*(od[0]*xd[16])))); -out[9] = ((od[0]*a[18])+(((od[1]*a[19])*(od[0]*xd[3]))+((od[1]*a[3])*(od[0]*xd[17])))); -out[10] = ((od[0]*a[20])+(((od[1]*a[21])*(od[0]*xd[3]))+((od[1]*a[3])*(od[0]*xd[18])))); -out[11] = ((od[0]*a[22])+(((od[1]*a[23])*(od[0]*xd[3]))+((od[1]*a[3])*(od[0]*xd[19])))); +out[4] = (od[0]*a[3]); +out[5] = (od[0]*a[4]); +out[6] = (od[0]*a[5]); +out[7] = (od[0]*a[6]); +out[8] = (od[0]*a[8]); +out[9] = (od[0]*a[9]); +out[10] = (od[0]*a[10]); +out[11] = (od[0]*a[11]); out[12] = (od[0]*xd[16]); out[13] = (od[0]*xd[17]); out[14] = (od[0]*xd[18]); @@ -79,19 +65,19 @@ out[16] = (real_t)(0.0000000000000000e+00); out[17] = (real_t)(0.0000000000000000e+00); out[18] = (real_t)(0.0000000000000000e+00); out[19] = (real_t)(0.0000000000000000e+00); -out[20] = ((od[0]*a[24])-(((od[1]*a[25])*(od[0]*xd[3]))+((od[1]*a[1])*(od[0]*xd[23])))); -out[21] = ((od[0]*a[26])+(((od[1]*a[27])*(od[0]*xd[3]))+((od[1]*a[3])*(od[0]*xd[23])))); +out[20] = (od[0]*a[12]); +out[21] = (od[0]*a[13]); out[22] = (od[0]*xd[23]); out[23] = (real_t)(1.0000000000000000e+00); } -/* Fixed step size:0.001 */ +/* Fixed step size:0.0025 */ int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ) { int error; int run1; -int numSteps[16] = {10, 29, 49, 68, 88, 107, 127, 146, 166, 186, 205, 225, 244, 264, 283, 303}; +int numSteps[16] = {4, 12, 20, 27, 35, 43, 51, 59, 66, 74, 82, 90, 98, 105, 113, 121}; int numInts = numSteps[rk_index]; acadoWorkspace.rk_ttt = 0.0000000000000000e+00; rk_eta[4] = 1.0000000000000000e+00; @@ -146,105 +132,105 @@ acadoWorkspace.rk_xxx[21] = + rk_eta[21]; acadoWorkspace.rk_xxx[22] = + rk_eta[22]; acadoWorkspace.rk_xxx[23] = + rk_eta[23]; acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); -acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[0] + rk_eta[0]; -acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[1] + rk_eta[1]; -acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[2] + rk_eta[2]; -acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[3] + rk_eta[3]; -acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[4] + rk_eta[4]; -acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[5] + rk_eta[5]; -acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[6] + rk_eta[6]; -acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[7] + rk_eta[7]; -acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[8] + rk_eta[8]; -acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[9] + rk_eta[9]; -acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[10] + rk_eta[10]; -acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[11] + rk_eta[11]; -acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[12] + rk_eta[12]; -acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[13] + rk_eta[13]; -acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[14] + rk_eta[14]; -acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[15] + rk_eta[15]; -acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[16] + rk_eta[16]; -acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[17] + rk_eta[17]; -acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[18] + rk_eta[18]; -acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[19] + rk_eta[19]; -acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[20] + rk_eta[20]; -acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[21] + rk_eta[21]; -acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[22] + rk_eta[22]; -acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[23] + rk_eta[23]; +acadoWorkspace.rk_xxx[0] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[0] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[1] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[2] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[3] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[4] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[5] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[6] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[7] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[8] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[9] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[10] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[11] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[12] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[13] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[14] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[15] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[16] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[17] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[18] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[19] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[20] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[21] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[22] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[23] + rk_eta[23]; acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 24 ]) ); -acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[24] + rk_eta[0]; -acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[25] + rk_eta[1]; -acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[26] + rk_eta[2]; -acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[27] + rk_eta[3]; -acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[28] + rk_eta[4]; -acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[29] + rk_eta[5]; -acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[30] + rk_eta[6]; -acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[31] + rk_eta[7]; -acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[32] + rk_eta[8]; -acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[33] + rk_eta[9]; -acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[34] + rk_eta[10]; -acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[35] + rk_eta[11]; -acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[36] + rk_eta[12]; -acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[37] + rk_eta[13]; -acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[38] + rk_eta[14]; -acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[39] + rk_eta[15]; -acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[40] + rk_eta[16]; -acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[41] + rk_eta[17]; -acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[42] + rk_eta[18]; -acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[43] + rk_eta[19]; -acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[44] + rk_eta[20]; -acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[45] + rk_eta[21]; -acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[46] + rk_eta[22]; -acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-04*acadoWorkspace.rk_kkk[47] + rk_eta[23]; +acadoWorkspace.rk_xxx[0] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[24] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[25] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[26] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[27] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[28] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[29] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[30] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[31] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[32] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[33] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[34] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[35] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[36] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[37] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[38] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[39] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[40] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[41] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[42] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[43] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[44] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[45] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[46] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)1.2500000000000000e-03*acadoWorkspace.rk_kkk[47] + rk_eta[23]; acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 48 ]) ); -acadoWorkspace.rk_xxx[0] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[48] + rk_eta[0]; -acadoWorkspace.rk_xxx[1] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[49] + rk_eta[1]; -acadoWorkspace.rk_xxx[2] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[50] + rk_eta[2]; -acadoWorkspace.rk_xxx[3] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[51] + rk_eta[3]; -acadoWorkspace.rk_xxx[4] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[52] + rk_eta[4]; -acadoWorkspace.rk_xxx[5] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[53] + rk_eta[5]; -acadoWorkspace.rk_xxx[6] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[54] + rk_eta[6]; -acadoWorkspace.rk_xxx[7] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[55] + rk_eta[7]; -acadoWorkspace.rk_xxx[8] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[56] + rk_eta[8]; -acadoWorkspace.rk_xxx[9] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[57] + rk_eta[9]; -acadoWorkspace.rk_xxx[10] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[58] + rk_eta[10]; -acadoWorkspace.rk_xxx[11] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[59] + rk_eta[11]; -acadoWorkspace.rk_xxx[12] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[60] + rk_eta[12]; -acadoWorkspace.rk_xxx[13] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[61] + rk_eta[13]; -acadoWorkspace.rk_xxx[14] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[62] + rk_eta[14]; -acadoWorkspace.rk_xxx[15] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[63] + rk_eta[15]; -acadoWorkspace.rk_xxx[16] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[64] + rk_eta[16]; -acadoWorkspace.rk_xxx[17] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[65] + rk_eta[17]; -acadoWorkspace.rk_xxx[18] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[66] + rk_eta[18]; -acadoWorkspace.rk_xxx[19] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[67] + rk_eta[19]; -acadoWorkspace.rk_xxx[20] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[68] + rk_eta[20]; -acadoWorkspace.rk_xxx[21] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[69] + rk_eta[21]; -acadoWorkspace.rk_xxx[22] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[70] + rk_eta[22]; -acadoWorkspace.rk_xxx[23] = + (real_t)1.0000000000000000e-03*acadoWorkspace.rk_kkk[71] + rk_eta[23]; +acadoWorkspace.rk_xxx[0] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[48] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[49] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[50] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[51] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[52] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[53] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[54] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[55] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[56] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[57] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[58] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[59] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[60] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[61] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[62] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[63] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[64] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[65] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[66] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[67] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[68] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[69] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[70] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)2.5000000000000001e-03*acadoWorkspace.rk_kkk[71] + rk_eta[23]; acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 72 ]) ); -rk_eta[0] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[0] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[24] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[48] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[72]; -rk_eta[1] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[1] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[25] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[49] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[73]; -rk_eta[2] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[2] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[26] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[50] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[74]; -rk_eta[3] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[3] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[27] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[51] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[75]; -rk_eta[4] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[4] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[28] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[52] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[76]; -rk_eta[5] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[5] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[29] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[53] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[77]; -rk_eta[6] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[6] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[30] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[54] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[78]; -rk_eta[7] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[7] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[31] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[55] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[79]; -rk_eta[8] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[8] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[32] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[56] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[80]; -rk_eta[9] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[9] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[33] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[57] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[81]; -rk_eta[10] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[10] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[34] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[58] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[82]; -rk_eta[11] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[11] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[35] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[59] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[83]; -rk_eta[12] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[12] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[36] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[60] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[84]; -rk_eta[13] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[13] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[37] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[61] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[85]; -rk_eta[14] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[14] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[38] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[62] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[86]; -rk_eta[15] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[15] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[39] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[63] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[87]; -rk_eta[16] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[16] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[40] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[64] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[88]; -rk_eta[17] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[17] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[41] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[65] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[89]; -rk_eta[18] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[18] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[42] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[66] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[90]; -rk_eta[19] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[19] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[43] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[67] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[91]; -rk_eta[20] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[20] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[44] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[68] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[92]; -rk_eta[21] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[21] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[45] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[69] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[93]; -rk_eta[22] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[22] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[46] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[70] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[94]; -rk_eta[23] += + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[23] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[47] + (real_t)3.3333333333333332e-04*acadoWorkspace.rk_kkk[71] + (real_t)1.6666666666666666e-04*acadoWorkspace.rk_kkk[95]; +rk_eta[0] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[0] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[24] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[48] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[72]; +rk_eta[1] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[1] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[25] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[49] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[73]; +rk_eta[2] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[2] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[26] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[50] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[74]; +rk_eta[3] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[3] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[27] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[51] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[75]; +rk_eta[4] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[4] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[28] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[52] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[76]; +rk_eta[5] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[5] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[29] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[53] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[77]; +rk_eta[6] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[6] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[30] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[54] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[78]; +rk_eta[7] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[7] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[31] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[55] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[79]; +rk_eta[8] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[8] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[32] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[56] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[80]; +rk_eta[9] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[9] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[33] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[57] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[81]; +rk_eta[10] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[10] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[34] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[58] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[82]; +rk_eta[11] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[11] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[35] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[59] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[83]; +rk_eta[12] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[12] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[36] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[60] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[84]; +rk_eta[13] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[13] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[37] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[61] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[85]; +rk_eta[14] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[14] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[38] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[62] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[86]; +rk_eta[15] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[15] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[39] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[63] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[87]; +rk_eta[16] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[16] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[40] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[64] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[88]; +rk_eta[17] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[17] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[41] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[65] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[89]; +rk_eta[18] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[18] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[42] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[66] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[90]; +rk_eta[19] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[19] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[43] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[67] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[91]; +rk_eta[20] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[20] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[44] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[68] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[92]; +rk_eta[21] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[21] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[45] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[69] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[93]; +rk_eta[22] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[22] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[46] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[70] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[94]; +rk_eta[23] += + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[23] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[47] + (real_t)8.3333333333333328e-04*acadoWorkspace.rk_kkk[71] + (real_t)4.1666666666666664e-04*acadoWorkspace.rk_kkk[95]; acadoWorkspace.rk_ttt += 1.0000000000000000e+00; } } diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp index 5b003f08b..723e484d6 100644 --- a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp @@ -41,7 +41,7 @@ /** Maximum number of constraints. */ #define QPOASES_NCMAX 32 /** Maximum number of working set recalculations. */ -#define QPOASES_NWSRMAX 1000 +#define QPOASES_NWSRMAX 50 /** Print level for qpOASES. */ #define QPOASES_PRINTLEVEL PL_NONE /** The value of EPS */ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c index 81a01da09..c8c7d27d6 100644 --- a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c @@ -2862,101 +2862,101 @@ acadoWorkspace.ub[1] = acadoWorkspace.Dx0[1]; acadoWorkspace.ub[2] = acadoWorkspace.Dx0[2]; acadoWorkspace.ub[3] = acadoWorkspace.Dx0[3]; tmp = acadoVariables.x[6] + acadoWorkspace.d[2]; -acadoWorkspace.lbA[0] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[0] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[0] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[0] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[7] + acadoWorkspace.d[3]; -acadoWorkspace.lbA[1] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[1] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[1] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[1] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[10] + acadoWorkspace.d[6]; -acadoWorkspace.lbA[2] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[2] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[2] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[2] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[11] + acadoWorkspace.d[7]; -acadoWorkspace.lbA[3] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[3] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[3] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[3] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[14] + acadoWorkspace.d[10]; -acadoWorkspace.lbA[4] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[4] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[4] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[4] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[15] + acadoWorkspace.d[11]; -acadoWorkspace.lbA[5] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[5] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[5] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[5] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[18] + acadoWorkspace.d[14]; -acadoWorkspace.lbA[6] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[6] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[6] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[6] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[19] + acadoWorkspace.d[15]; -acadoWorkspace.lbA[7] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[7] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[7] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[7] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[22] + acadoWorkspace.d[18]; -acadoWorkspace.lbA[8] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[8] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[8] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[8] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[23] + acadoWorkspace.d[19]; -acadoWorkspace.lbA[9] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[9] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[9] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[9] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[26] + acadoWorkspace.d[22]; -acadoWorkspace.lbA[10] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[10] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[10] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[10] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[27] + acadoWorkspace.d[23]; -acadoWorkspace.lbA[11] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[11] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[11] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[11] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[30] + acadoWorkspace.d[26]; -acadoWorkspace.lbA[12] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[12] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[12] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[12] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[31] + acadoWorkspace.d[27]; -acadoWorkspace.lbA[13] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[13] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[13] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[13] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[34] + acadoWorkspace.d[30]; -acadoWorkspace.lbA[14] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[14] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[14] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[14] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[35] + acadoWorkspace.d[31]; -acadoWorkspace.lbA[15] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[15] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[15] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[15] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[38] + acadoWorkspace.d[34]; -acadoWorkspace.lbA[16] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[16] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[16] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[16] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[39] + acadoWorkspace.d[35]; -acadoWorkspace.lbA[17] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[17] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[17] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[17] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[42] + acadoWorkspace.d[38]; -acadoWorkspace.lbA[18] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[18] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[18] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[18] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[43] + acadoWorkspace.d[39]; -acadoWorkspace.lbA[19] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[19] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[19] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[19] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[46] + acadoWorkspace.d[42]; -acadoWorkspace.lbA[20] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[20] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[20] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[20] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[47] + acadoWorkspace.d[43]; -acadoWorkspace.lbA[21] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[21] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[21] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[21] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[50] + acadoWorkspace.d[46]; -acadoWorkspace.lbA[22] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[22] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[22] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[22] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[51] + acadoWorkspace.d[47]; -acadoWorkspace.lbA[23] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[23] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[23] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[23] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[54] + acadoWorkspace.d[50]; -acadoWorkspace.lbA[24] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[24] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[24] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[24] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[55] + acadoWorkspace.d[51]; -acadoWorkspace.lbA[25] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[25] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[25] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[25] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[58] + acadoWorkspace.d[54]; -acadoWorkspace.lbA[26] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[26] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[26] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[26] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[59] + acadoWorkspace.d[55]; -acadoWorkspace.lbA[27] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[27] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[27] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[27] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[62] + acadoWorkspace.d[58]; -acadoWorkspace.lbA[28] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[28] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[28] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[28] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[63] + acadoWorkspace.d[59]; -acadoWorkspace.lbA[29] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[29] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[29] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[29] = (real_t)8.7266462599716477e-01 - tmp; tmp = acadoVariables.x[66] + acadoWorkspace.d[62]; -acadoWorkspace.lbA[30] = (real_t)-1.5707963268000000e+00 - tmp; -acadoWorkspace.ubA[30] = (real_t)1.5707963268000000e+00 - tmp; +acadoWorkspace.lbA[30] = (real_t)-1.5707963267948966e+00 - tmp; +acadoWorkspace.ubA[30] = (real_t)1.5707963267948966e+00 - tmp; tmp = acadoVariables.x[67] + acadoWorkspace.d[63]; -acadoWorkspace.lbA[31] = (real_t)-8.7266462600000005e-01 - tmp; -acadoWorkspace.ubA[31] = (real_t)8.7266462600000005e-01 - tmp; +acadoWorkspace.lbA[31] = (real_t)-8.7266462599716477e-01 - tmp; +acadoWorkspace.ubA[31] = (real_t)8.7266462599716477e-01 - tmp; } diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index f92c6c5e9..0c258d8db 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -2,10 +2,10 @@ import os import math import numpy as np from common.realtime import sec_since_boot, DT_MDL -from common.numpy_fast import interp, clip +from common.numpy_fast import interp from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.lateral_mpc import libmpc_py -from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT, MPC_N, CAR_ROTATION_RADIUS +from selfdrive.controls.lib.drive_helpers import CONTROL_N, MPC_COST_LAT, LAT_MPC_N, CAR_ROTATION_RADIUS from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE from selfdrive.config import Conversions as CV import cereal.messaging as messaging @@ -18,9 +18,6 @@ LOG_MPC = os.environ.get('LOG_MPC', False) LANE_CHANGE_SPEED_MIN = 30 * CV.MPH_TO_MS LANE_CHANGE_TIME_MAX = 10. -# this corresponds to 80deg/s and 20deg/s steering angle in a toyota corolla -MAX_CURVATURE_RATES = [0.03762194918267951, 0.003441203371932992] -MAX_CURVATURE_RATE_SPEEDS = [0, 35] DESIRES = { LaneChangeDirection.none: { @@ -173,12 +170,15 @@ class LateralPlanner(): # Heading cost is useful at low speed, otherwise end of plan can be off-heading heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.0]) self.libmpc.set_weights(path_cost, heading_cost, CP.steerRateCost) - y_pts = np.interp(v_ego * self.t_idxs[:MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:,1]) - heading_pts = np.interp(v_ego * self.t_idxs[:MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) + y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:,1]) + heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) self.y_pts = y_pts - assert len(y_pts) == MPC_N + 1 - assert len(heading_pts) == MPC_N + 1 + assert len(y_pts) == LAT_MPC_N + 1 + assert len(heading_pts) == LAT_MPC_N + 1 + # for now CAR_ROTATION_RADIUS is disabled + # to use it, enable it in the MPC + assert abs(CAR_ROTATION_RADIUS) < 1e-3 self.libmpc.run_mpc(self.cur_state, self.mpc_solution, float(v_ego), CAR_ROTATION_RADIUS, @@ -188,29 +188,7 @@ class LateralPlanner(): self.cur_state.x = 0.0 self.cur_state.y = 0.0 self.cur_state.psi = 0.0 - self.cur_state.curvature = interp(DT_MDL, self.t_idxs[:MPC_N + 1], self.mpc_solution.curvature) - - # TODO this needs more thought, use .2s extra for now to estimate other delays - delay = CP.steerActuatorDelay + .2 - current_curvature = self.mpc_solution.curvature[0] - psi = interp(delay, self.t_idxs[:MPC_N + 1], self.mpc_solution.psi) - next_curvature_rate = self.mpc_solution.curvature_rate[0] - - # MPC can plan to turn the wheel and turn back before t_delay. This means - # in high delay cases some corrections never even get commanded. So just use - # psi to calculate a simple linearization of desired curvature - curvature_diff_from_psi = psi / (max(v_ego, 1e-1) * delay) - current_curvature - next_curvature = current_curvature + 2 * curvature_diff_from_psi - - self.desired_curvature = next_curvature - self.desired_curvature_rate = next_curvature_rate - max_curvature_rate = interp(v_ego, MAX_CURVATURE_RATE_SPEEDS, MAX_CURVATURE_RATES) - self.safe_desired_curvature_rate = clip(self.desired_curvature_rate, - -max_curvature_rate, - max_curvature_rate) - self.safe_desired_curvature = clip(self.desired_curvature, - self.safe_desired_curvature - max_curvature_rate/DT_MDL, - self.safe_desired_curvature + max_curvature_rate/DT_MDL) + self.cur_state.curvature = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.mpc_solution.curvature) # Check for infeasable MPC solution mpc_nans = any(math.isnan(x) for x in self.mpc_solution.curvature) @@ -234,15 +212,13 @@ class LateralPlanner(): plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'modelV2']) plan_send.lateralPlan.laneWidth = float(self.LP.lane_width) plan_send.lateralPlan.dPathPoints = [float(x) for x in self.y_pts] + plan_send.lateralPlan.psis = [float(x) for x in self.mpc_solution.psi[0:CONTROL_N]] + plan_send.lateralPlan.curvatures = [float(x) for x in self.mpc_solution.curvature[0:CONTROL_N]] + plan_send.lateralPlan.curvatureRates = [float(x) for x in self.mpc_solution.curvature_rate[0:CONTROL_N-1]] +[0.0] plan_send.lateralPlan.lProb = float(self.LP.lll_prob) plan_send.lateralPlan.rProb = float(self.LP.rll_prob) plan_send.lateralPlan.dProb = float(self.LP.d_prob) - plan_send.lateralPlan.rawCurvature = float(self.desired_curvature) - plan_send.lateralPlan.rawCurvatureRate = float(self.desired_curvature_rate) - plan_send.lateralPlan.curvature = float(self.safe_desired_curvature) - plan_send.lateralPlan.curvatureRate = float(self.safe_desired_curvature_rate) - plan_send.lateralPlan.mpcSolutionValid = bool(plan_solution_valid) plan_send.lateralPlan.desire = self.desire diff --git a/selfdrive/controls/lib/lead_mpc.py b/selfdrive/controls/lib/lead_mpc.py new file mode 100644 index 000000000..da5bbc25f --- /dev/null +++ b/selfdrive/controls/lib/lead_mpc.py @@ -0,0 +1,111 @@ +import math +import numpy as np +from common.numpy_fast import interp +from common.realtime import sec_since_boot +from selfdrive.modeld.constants import T_IDXS +from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU +from selfdrive.controls.lib.lead_mpc_lib import libmpc_py +from selfdrive.controls.lib.drive_helpers import MPC_COST_LONG, CONTROL_N +from selfdrive.swaglog import cloudlog + +MPC_T = list(np.arange(0,1.,.2)) + list(np.arange(1.,10.6,.6)) + + +class LeadMpc(): + def __init__(self, mpc_id): + self.lead_id = mpc_id + + self.reset_mpc() + self.prev_lead_status = False + self.prev_lead_x = 0.0 + self.new_lead = False + + self.last_cloudlog_t = 0.0 + self.n_its = 0 + self.duration = 0 + self.status = False + + self.v_solution = np.zeros(CONTROL_N) + self.a_solution = np.zeros(CONTROL_N) + self.j_solution = np.zeros(CONTROL_N) + + def reset_mpc(self): + ffi, self.libmpc = libmpc_py.get_libmpc(self.lead_id) + self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, + MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + + self.mpc_solution = ffi.new("log_t *") + self.cur_state = ffi.new("state_t *") + self.cur_state[0].v_ego = 0 + self.cur_state[0].a_ego = 0 + self.a_lead_tau = _LEAD_ACCEL_TAU + + def set_cur_state(self, v, a): + v_safe = max(v, 1e-3) + a_safe = a + self.cur_state[0].v_ego = v_safe + self.cur_state[0].a_ego = a_safe + + def update(self, CS, radarstate, v_cruise): + v_ego = CS.vEgo + if self.lead_id == 0: + lead = radarstate.leadOne + else: + lead = radarstate.leadTwo + self.status = lead.status + + # Setup current mpc state + self.cur_state[0].x_ego = 0.0 + + if lead is not None and lead.status: + x_lead = lead.dRel + v_lead = max(0.0, lead.vLead) + a_lead = lead.aLeadK + + if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): + v_lead = 0.0 + a_lead = 0.0 + + self.a_lead_tau = lead.aLeadTau + self.new_lead = False + if not self.prev_lead_status or abs(x_lead - self.prev_lead_x) > 2.5: + self.libmpc.init_with_simulation(v_ego, x_lead, v_lead, a_lead, self.a_lead_tau) + self.new_lead = True + + self.prev_lead_status = True + self.prev_lead_x = x_lead + self.cur_state[0].x_l = x_lead + self.cur_state[0].v_l = v_lead + else: + self.prev_lead_status = False + # Fake a fast lead car, so mpc keeps running + self.cur_state[0].x_l = 50.0 + self.cur_state[0].v_l = v_ego + 10.0 + a_lead = 0.0 + self.a_lead_tau = _LEAD_ACCEL_TAU + + # Calculate mpc + t = sec_since_boot() + self.n_its = self.libmpc.run_mpc(self.cur_state, self.mpc_solution, self.a_lead_tau, a_lead) + self.v_solution = interp(T_IDXS[:CONTROL_N], MPC_T, self.mpc_solution.v_ego) + self.a_solution = interp(T_IDXS[:CONTROL_N], MPC_T, self.mpc_solution.a_ego) + self.j_solution = interp(T_IDXS[:CONTROL_N], MPC_T[:-1], self.mpc_solution.j_ego) + self.duration = int((sec_since_boot() - t) * 1e9) + + # Reset if NaN or goes through lead car + crashing = any(lead - ego < -50 for (lead, ego) in zip(self.mpc_solution[0].x_l, self.mpc_solution[0].x_ego)) + nans = any(math.isnan(x) for x in self.mpc_solution[0].v_ego) + backwards = min(self.mpc_solution[0].v_ego) < -0.01 + + if ((backwards or crashing) and self.prev_lead_status) or nans: + if t > self.last_cloudlog_t + 5.0: + self.last_cloudlog_t = t + cloudlog.warning("Longitudinal mpc %d reset - backwards: %s crashing: %s nan: %s" % ( + self.lead_id, backwards, crashing, nans)) + + self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, + MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + self.cur_state[0].v_ego = v_ego + self.cur_state[0].a_ego = 0.0 + self.a_mpc = CS.aEgo + self.prev_lead_status = False diff --git a/selfdrive/controls/lib/longitudinal_mpc/.gitignore b/selfdrive/controls/lib/lead_mpc_lib/.gitignore similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/.gitignore rename to selfdrive/controls/lib/lead_mpc_lib/.gitignore diff --git a/selfdrive/controls/lib/longitudinal_mpc/SConscript b/selfdrive/controls/lib/lead_mpc_lib/SConscript similarity index 96% rename from selfdrive/controls/lib/longitudinal_mpc/SConscript rename to selfdrive/controls/lib/lead_mpc_lib/SConscript index 584d5103e..94deb5d6f 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/SConscript +++ b/selfdrive/controls/lib/lead_mpc_lib/SConscript @@ -44,5 +44,5 @@ if GetOption('mpc_generate'): mpc_files = ["longitudinal_mpc.c"] + generated_c +env.SharedLibrary('mpc0', mpc_files, LIBS=['m', 'qpoases'], LIBPATH=['lib_qp'], CPPPATH=cpp_path) env.SharedLibrary('mpc1', mpc_files, LIBS=['m', 'qpoases'], LIBPATH=['lib_qp'], CPPPATH=cpp_path) -env.SharedLibrary('mpc2', mpc_files, LIBS=['m', 'qpoases'], LIBPATH=['lib_qp'], CPPPATH=cpp_path) diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/__init__.py b/selfdrive/controls/lib/lead_mpc_lib/__init__.py similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc_model/__init__.py rename to selfdrive/controls/lib/lead_mpc_lib/__init__.py diff --git a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp b/selfdrive/controls/lib/lead_mpc_lib/generator.cpp similarity index 98% rename from selfdrive/controls/lib/longitudinal_mpc/generator.cpp rename to selfdrive/controls/lib/lead_mpc_lib/generator.cpp index a34fbc351..f633db71e 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp +++ b/selfdrive/controls/lib/lead_mpc_lib/generator.cpp @@ -77,7 +77,7 @@ int main( ) mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); mpc.set( INTEGRATOR_TYPE, INT_RK4 ); mpc.set( NUM_INTEGRATOR_STEPS, controlHorizon); - mpc.set( MAX_NUM_QP_ITERATIONS, 500); + mpc.set( MAX_NUM_QP_ITERATIONS, 50); mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.c b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_auxiliary_functions.c similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.c rename to selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_auxiliary_functions.c diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.h b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_auxiliary_functions.h similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.h rename to selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_common.h similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h rename to selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_common.h diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_integrator.c similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c rename to selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_integrator.c diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.cpp b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_qpoases_interface.cpp similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.cpp rename to selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_qpoases_interface.cpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_qpoases_interface.hpp similarity index 98% rename from selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp rename to selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_qpoases_interface.hpp index 8a58805f8..1409d1e89 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp +++ b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_qpoases_interface.hpp @@ -41,7 +41,7 @@ /** Maximum number of constraints. */ #define QPOASES_NCMAX 20 /** Maximum number of working set recalculations. */ -#define QPOASES_NWSRMAX 500 +#define QPOASES_NWSRMAX 50 /** Print level for qpOASES. */ #define QPOASES_PRINTLEVEL PL_NONE /** The value of EPS */ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c b/selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_solver.c similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c rename to selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/acado_solver.c diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py b/selfdrive/controls/lib/lead_mpc_lib/libmpc_py.py similarity index 93% rename from selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py rename to selfdrive/controls/lib/lead_mpc_lib/libmpc_py.py index c40b4e071..d6d11be01 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py +++ b/selfdrive/controls/lib/lead_mpc_lib/libmpc_py.py @@ -35,7 +35,7 @@ def _get_libmpc(mpc_id): return (ffi, ffi.dlopen(libmpc_fn)) -mpcs = [_get_libmpc(1), _get_libmpc(2)] +mpcs = [_get_libmpc(0), _get_libmpc(1)] def get_libmpc(mpc_id): - return mpcs[mpc_id - 1] + return mpcs[mpc_id] diff --git a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c b/selfdrive/controls/lib/lead_mpc_lib/longitudinal_mpc.c similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c rename to selfdrive/controls/lib/lead_mpc_lib/longitudinal_mpc.c diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index 0e51d521d..6f0db25fc 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -1,122 +1,71 @@ -import os +import numpy as np import math -import cereal.messaging as messaging from selfdrive.swaglog import cloudlog from common.realtime import sec_since_boot -from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU -from selfdrive.controls.lib.longitudinal_mpc import libmpc_py -from selfdrive.controls.lib.drive_helpers import MPC_COST_LONG - -LOG_MPC = os.environ.get('LOG_MPC', False) +from selfdrive.controls.lib.longitudinal_mpc_lib import libmpc_py +from selfdrive.controls.lib.drive_helpers import LON_MPC_N +from selfdrive.modeld.constants import T_IDXS class LongitudinalMpc(): - def __init__(self, mpc_id): - self.mpc_id = mpc_id - - self.setup_mpc() - self.v_mpc = 0.0 - self.v_mpc_future = 0.0 - self.a_mpc = 0.0 - self.v_cruise = 0.0 - self.prev_lead_status = False - self.prev_lead_x = 0.0 - self.new_lead = False - + def __init__(self): + self.reset_mpc() self.last_cloudlog_t = 0.0 - self.n_its = 0 - self.duration = 0 + self.ts = list(range(10)) + self.status = True + self.min_a = -1.2 + self.max_a = 1.2 - def publish(self, pm): - if LOG_MPC: - qp_iterations = max(0, self.n_its) - dat = messaging.new_message('liveLongitudinalMpc') - dat.liveLongitudinalMpc.xEgo = list(self.mpc_solution[0].x_ego) - dat.liveLongitudinalMpc.vEgo = list(self.mpc_solution[0].v_ego) - dat.liveLongitudinalMpc.aEgo = list(self.mpc_solution[0].a_ego) - dat.liveLongitudinalMpc.xLead = list(self.mpc_solution[0].x_l) - dat.liveLongitudinalMpc.vLead = list(self.mpc_solution[0].v_l) - dat.liveLongitudinalMpc.cost = self.mpc_solution[0].cost - dat.liveLongitudinalMpc.aLeadTau = self.a_lead_tau - dat.liveLongitudinalMpc.qpIterations = qp_iterations - dat.liveLongitudinalMpc.mpcId = self.mpc_id - dat.liveLongitudinalMpc.calculationTime = self.duration - pm.send('liveLongitudinalMpc', dat) - def setup_mpc(self): - ffi, self.libmpc = libmpc_py.get_libmpc(self.mpc_id) - self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, - MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + def reset_mpc(self): + self.libmpc = libmpc_py.libmpc + self.libmpc.init(0.0, 1.0, 0.0, 50.0, 10000.0) - self.mpc_solution = ffi.new("log_t *") - self.cur_state = ffi.new("state_t *") + self.mpc_solution = libmpc_py.ffi.new("log_t *") + self.cur_state = libmpc_py.ffi.new("state_t *") + + self.cur_state[0].x_ego = 0 self.cur_state[0].v_ego = 0 self.cur_state[0].a_ego = 0 - self.a_lead_tau = _LEAD_ACCEL_TAU + + self.v_solution = [0.0 for i in range(len(T_IDXS))] + self.a_solution = [0.0 for i in range(len(T_IDXS))] + self.j_solution = [0.0 for i in range(len(T_IDXS)-1)] + + def set_accel_limits(self, min_a, max_a): + self.min_a = min_a + self.max_a = max_a def set_cur_state(self, v, a): - self.cur_state[0].v_ego = v - self.cur_state[0].a_ego = a - - def update(self, CS, lead): - v_ego = CS.vEgo - - # Setup current mpc state + v_safe = max(v, 1e-2) + a_safe = min(a, self.max_a - 1e-2) + a_safe = max(a_safe, self.min_a + 1e-2) self.cur_state[0].x_ego = 0.0 + self.cur_state[0].v_ego = v_safe + self.cur_state[0].a_ego = a_safe - if lead is not None and lead.status: - x_lead = lead.dRel - v_lead = max(0.0, lead.vLead) - a_lead = lead.aLeadK - - if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): - v_lead = 0.0 - a_lead = 0.0 - - self.a_lead_tau = lead.aLeadTau - self.new_lead = False - if not self.prev_lead_status or abs(x_lead - self.prev_lead_x) > 2.5: - self.libmpc.init_with_simulation(self.v_mpc, x_lead, v_lead, a_lead, self.a_lead_tau) - self.new_lead = True - - self.prev_lead_status = True - self.prev_lead_x = x_lead - self.cur_state[0].x_l = x_lead - self.cur_state[0].v_l = v_lead - else: - self.prev_lead_status = False - # Fake a fast lead car, so mpc keeps running - self.cur_state[0].x_l = 50.0 - self.cur_state[0].v_l = v_ego + 10.0 - a_lead = 0.0 - self.a_lead_tau = _LEAD_ACCEL_TAU + def update(self, carstate, model, v_cruise): + v_cruise_clipped = np.clip(v_cruise, self.cur_state[0].v_ego - 10., self.cur_state[0].v_ego + 10.0) + poss = v_cruise_clipped * np.array(T_IDXS[:LON_MPC_N+1]) + speeds = v_cruise_clipped * np.ones(LON_MPC_N+1) + accels = np.zeros(LON_MPC_N+1) # Calculate mpc - t = sec_since_boot() - self.n_its = self.libmpc.run_mpc(self.cur_state, self.mpc_solution, self.a_lead_tau, a_lead) - self.duration = int((sec_since_boot() - t) * 1e9) + self.libmpc.run_mpc(self.cur_state, self.mpc_solution, + list(poss), list(speeds), list(accels), + self.min_a, self.max_a) - # Get solution. MPC timestep is 0.2 s, so interpolation to 0.05 s is needed - self.v_mpc = self.mpc_solution[0].v_ego[1] - self.a_mpc = self.mpc_solution[0].a_ego[1] - self.v_mpc_future = self.mpc_solution[0].v_ego[10] + self.v_solution = list(self.mpc_solution.v_ego) + self.a_solution = list(self.mpc_solution.a_ego) + self.j_solution = list(self.mpc_solution.j_ego) # Reset if NaN or goes through lead car - crashing = any(lead - ego < -50 for (lead, ego) in zip(self.mpc_solution[0].x_l, self.mpc_solution[0].x_ego)) nans = any(math.isnan(x) for x in self.mpc_solution[0].v_ego) - backwards = min(self.mpc_solution[0].v_ego) < -0.01 - if ((backwards or crashing) and self.prev_lead_status) or nans: + t = sec_since_boot() + if nans: if t > self.last_cloudlog_t + 5.0: self.last_cloudlog_t = t - cloudlog.warning("Longitudinal mpc %d reset - backwards: %s crashing: %s nan: %s" % ( - self.mpc_id, backwards, crashing, nans)) - - self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, - MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) - self.cur_state[0].v_ego = v_ego - self.cur_state[0].a_ego = 0.0 - self.v_mpc = v_ego - self.a_mpc = CS.aEgo - self.prev_lead_status = False + cloudlog.warning("Longitudinal model mpc reset - nans") + self.reset_mpc() diff --git a/selfdrive/controls/lib/long_mpc_model.py b/selfdrive/controls/lib/long_mpc_model.py deleted file mode 100644 index b3a55b8f0..000000000 --- a/selfdrive/controls/lib/long_mpc_model.py +++ /dev/null @@ -1,73 +0,0 @@ -import numpy as np -import math - -from selfdrive.swaglog import cloudlog -from common.realtime import sec_since_boot -from selfdrive.controls.lib.longitudinal_mpc_model import libmpc_py - - -class LongitudinalMpcModel(): - def __init__(self): - - self.setup_mpc() - self.v_mpc = 0.0 - self.v_mpc_future = 0.0 - self.a_mpc = 0.0 - self.last_cloudlog_t = 0.0 - self.ts = list(range(10)) - - self.valid = False - - def setup_mpc(self, v_ego=0.0): - self.libmpc = libmpc_py.libmpc - self.libmpc.init(1.0, 1.0, 1.0, 1.0, 1.0) - self.libmpc.init_with_simulation(v_ego) - - self.mpc_solution = libmpc_py.ffi.new("log_t *") - self.cur_state = libmpc_py.ffi.new("state_t *") - - self.cur_state[0].x_ego = 0 - self.cur_state[0].v_ego = 0 - self.cur_state[0].a_ego = 0 - - def set_cur_state(self, v, a): - self.cur_state[0].x_ego = 0.0 - self.cur_state[0].v_ego = v - self.cur_state[0].a_ego = a - - def update(self, v_ego, a_ego, poss, speeds, accels): - if len(poss) == 0: - self.valid = False - return - - x_poly = list(map(float, np.polyfit(self.ts, poss, 3))) - v_poly = list(map(float, np.polyfit(self.ts, speeds, 3))) - a_poly = list(map(float, np.polyfit(self.ts, accels, 3))) - - # Calculate mpc - self.libmpc.run_mpc(self.cur_state, self.mpc_solution, x_poly, v_poly, a_poly) - - # Get solution. MPC timestep is 0.2 s, so interpolation to 0.05 s is needed - self.v_mpc = self.mpc_solution[0].v_ego[1] - self.a_mpc = self.mpc_solution[0].a_ego[1] - self.v_mpc_future = self.mpc_solution[0].v_ego[10] - self.valid = True - - # Reset if NaN or goes through lead car - nans = any(math.isnan(x) for x in self.mpc_solution[0].v_ego) - - t = sec_since_boot() - if nans: - if t > self.last_cloudlog_t + 5.0: - self.last_cloudlog_t = t - cloudlog.warning("Longitudinal model mpc reset - backwards") - - self.libmpc.init(1.0, 1.0, 1.0, 1.0, 1.0) - self.libmpc.init_with_simulation(v_ego) - - self.cur_state[0].v_ego = v_ego - self.cur_state[0].a_ego = 0.0 - - self.v_mpc = v_ego - self.a_mpc = a_ego - self.valid = False diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index 2ead3474b..695615e0e 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -1,6 +1,8 @@ from cereal import log from common.numpy_fast import clip, interp from selfdrive.controls.lib.pid import PIController +from selfdrive.controls.lib.drive_helpers import CONTROL_N +from selfdrive.modeld.constants import T_IDXS LongCtrlState = log.ControlsState.LongControlState @@ -12,6 +14,7 @@ BRAKE_THRESHOLD_TO_PID = 0.2 BRAKE_STOPPING_TARGET = 0.5 # apply at least this amount of brake to maintain the vehicle stationary RATE = 100.0 +DEFAULT_LONG_LAG = 0.15 def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid, @@ -66,8 +69,20 @@ class LongControl(): self.pid.reset() self.v_pid = v_pid - def update(self, active, CS, v_target, v_target_future, a_target, CP): + def update(self, active, CS, CP, long_plan): """Update longitudinal control. This updates the state machine and runs a PID loop""" + # Interp control trajectory + # TODO estimate car specific lag, use .5s for now + if len(long_plan.speeds) == CONTROL_N: + v_target = interp(DEFAULT_LONG_LAG, T_IDXS[:CONTROL_N], long_plan.speeds) + v_target_future = long_plan.speeds[-1] + a_target = interp(DEFAULT_LONG_LAG, T_IDXS[:CONTROL_N], long_plan.accels) + else: + v_target = 0.0 + v_target_future = 0.0 + a_target = 0.0 + + # Actuation limits gas_max = interp(CS.vEgo, CP.gasMaxBP, CP.gasMaxV) brake_max = interp(CS.vEgo, CP.brakeMaxBP, CP.brakeMaxV) @@ -119,4 +134,4 @@ class LongControl(): final_gas = clip(output_gb, 0., gas_max) final_brake = -clip(output_gb, -brake_max, 0.) - return final_gas, final_brake + return final_gas, final_brake, v_target, a_target diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/.gitignore b/selfdrive/controls/lib/longitudinal_mpc_lib/.gitignore similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc_model/.gitignore rename to selfdrive/controls/lib/longitudinal_mpc_lib/.gitignore diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript new file mode 100644 index 000000000..19387d4ae --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript @@ -0,0 +1,47 @@ +Import('env', 'arch') + +cpp_path = [ + "#", + "#selfdrive", + "#phonelibs/acado/include", + "#phonelibs/acado/include/acado", + "#phonelibs/qpoases/INCLUDE", + "#phonelibs/qpoases/INCLUDE/EXTRAS", + "#phonelibs/qpoases/SRC/", + "#phonelibs/qpoases", + "lib_mpc_export", +] + +generated_c = [ + 'lib_mpc_export/acado_auxiliary_functions.c', + 'lib_mpc_export/acado_qpoases_interface.cpp', + 'lib_mpc_export/acado_integrator.c', + 'lib_mpc_export/acado_solver.c', +] + +generated_h = [ + 'lib_mpc_export/acado_common.h', + 'lib_mpc_export/acado_auxiliary_functions.h', + 'lib_mpc_export/acado_qpoases_interface.hpp', +] + +interface_dir = Dir('lib_mpc_export') + +SConscript(['#phonelibs/qpoases/SConscript'], variant_dir='lib_qp', exports=['interface_dir']) + +if GetOption('mpc_generate'): + generator_cpp = File('generator.cpp') + + acado_libs = [File(f"#phonelibs/acado/{arch}/lib/libacado_toolkit.a"), + File(f"#phonelibs/acado/{arch}/lib/libacado_casadi.a"), + File(f"#phonelibs/acado/{arch}/lib/libacado_csparse.a")] + + generator = env.Program('generator', generator_cpp, LIBS=acado_libs, CPPPATH=cpp_path, + CCFLAGS=env['CCFLAGS'] + ["-Wno-deprecated", "-Wno-overloaded-shift-op-parentheses"]) + + cmd = f"cd {Dir('.').get_abspath()} && {generator[0].get_abspath()}" + env.Command(generated_c + generated_h, generator, cmd) + + +mpc_files = ["longitudinal_mpc.c"] + generated_c +env.SharedLibrary('mpc', mpc_files, LIBS=['m', 'qpoases'], LIBPATH=['lib_qp'], CPPPATH=cpp_path) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/__init__.py b/selfdrive/controls/lib/longitudinal_mpc_lib/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/generator.cpp b/selfdrive/controls/lib/longitudinal_mpc_lib/generator.cpp new file mode 100644 index 000000000..d308d102d --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/generator.cpp @@ -0,0 +1,82 @@ +#include +#include "selfdrive/common/modeldata.h" + +using namespace std; + + +int main( ) +{ + USING_NAMESPACE_ACADO + + + DifferentialEquation f; + + DifferentialState x_ego, v_ego, a_ego; + DifferentialState dummy_0; + OnlineData min_a, max_a; + + Control j_ego, accel_slack; + + // Equations of motion + f << dot(x_ego) == v_ego; + f << dot(v_ego) == a_ego; + f << dot(a_ego) == j_ego; + f << dot(dummy_0) == accel_slack; + + // Running cost + Function h; + h << x_ego; + h << v_ego; + h << a_ego; + h << j_ego; + h << accel_slack; + + // Weights are defined in mpc. + BMatrix Q(5,5); Q.setAll(true); + + // Terminal cost + Function hN; + hN << x_ego; + hN << v_ego; + hN << a_ego; + + // Weights are defined in mpc. + BMatrix QN(3,3); QN.setAll(true); + + double T_IDXS_ARR[LON_MPC_N + 1]; + memcpy(T_IDXS_ARR, T_IDXS, (LON_MPC_N + 1) * sizeof(double)); + Grid times(LON_MPC_N + 1, T_IDXS_ARR); + OCP ocp(times); + ocp.subjectTo(f); + + ocp.minimizeLSQ(Q, h); + ocp.minimizeLSQEndTerm(QN, hN); + + ocp.subjectTo( 0.0 <= v_ego); + ocp.subjectTo( 0.0 <= a_ego - min_a + accel_slack); + ocp.subjectTo( a_ego - max_a + accel_slack <= 0.0); + ocp.setNOD(2); + + OCPexport mpc(ocp); + mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); + mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); + mpc.set( INTEGRATOR_TYPE, INT_RK4 ); + mpc.set( NUM_INTEGRATOR_STEPS, 1000); + mpc.set( MAX_NUM_QP_ITERATIONS, 50); + mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); + + mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); + mpc.set( QP_SOLVER, QP_QPOASES ); + mpc.set( HOTSTART_QP, YES ); + mpc.set( GENERATE_TEST_FILE, NO); + mpc.set( GENERATE_MAKE_FILE, NO ); + mpc.set( GENERATE_MATLAB_INTERFACE, NO ); + mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); + + if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) + exit( EXIT_FAILURE ); + + mpc.printDimensionsQP( ); + + return EXIT_SUCCESS; +} diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_auxiliary_functions.c b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_auxiliary_functions.c similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_auxiliary_functions.c rename to selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_auxiliary_functions.c diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_auxiliary_functions.h b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_auxiliary_functions.h similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_auxiliary_functions.h rename to selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_common.h b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_common.h similarity index 65% rename from selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_common.h rename to selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_common.h index cf8c42478..4951fae46 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_common.h +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_common.h @@ -62,13 +62,13 @@ extern "C" /** Indicator for fixed initial state. */ #define ACADO_INITIAL_STATE_FIXED 1 /** Number of control/estimation intervals. */ -#define ACADO_N 20 +#define ACADO_N 32 /** Number of online data values. */ -#define ACADO_NOD 12 +#define ACADO_NOD 2 /** Number of path constraints. */ -#define ACADO_NPAC 0 +#define ACADO_NPAC 2 /** Number of control variables. */ -#define ACADO_NU 1 +#define ACADO_NU 2 /** Number of differential variables. */ #define ACADO_NX 4 /** Number of algebraic variables. */ @@ -78,9 +78,9 @@ extern "C" /** Number of references/measurements per node on the first N nodes. */ #define ACADO_NY 5 /** Number of references/measurements on the last (N + 1)st node. */ -#define ACADO_NYN 4 +#define ACADO_NYN 3 /** Total number of QP optimization variables. */ -#define ACADO_QP_NV 24 +#define ACADO_QP_NV 68 /** Number of Runge-Kutta stages per integration step. */ #define ACADO_RK_NSTAGES 4 /** Providing interface for arrival cost. */ @@ -102,41 +102,41 @@ extern "C" typedef struct ACADOvariables_ { int dummy; -/** Matrix of size: 21 x 4 (row major format) +/** Matrix of size: 33 x 4 (row major format) * - * Matrix containing 21 differential variable vectors. + * Matrix containing 33 differential variable vectors. */ -real_t x[ 84 ]; +real_t x[ 132 ]; -/** Column vector of size: 20 +/** Matrix of size: 32 x 2 (row major format) * - * Matrix containing 20 control variable vectors. + * Matrix containing 32 control variable vectors. */ -real_t u[ 20 ]; +real_t u[ 64 ]; -/** Matrix of size: 21 x 12 (row major format) +/** Matrix of size: 33 x 2 (row major format) * - * Matrix containing 21 online data vectors. + * Matrix containing 33 online data vectors. */ -real_t od[ 252 ]; +real_t od[ 66 ]; -/** Column vector of size: 100 +/** Column vector of size: 160 * - * Matrix containing 20 reference/measurement vectors of size 5 for first 20 nodes. + * Matrix containing 32 reference/measurement vectors of size 5 for first 32 nodes. */ -real_t y[ 100 ]; +real_t y[ 160 ]; -/** Column vector of size: 4 +/** Column vector of size: 3 * - * Reference/measurement vector for the 21. node. + * Reference/measurement vector for the 33. node. */ -real_t yN[ 4 ]; +real_t yN[ 3 ]; -/** Matrix of size: 100 x 5 (row major format) */ -real_t W[ 500 ]; +/** Matrix of size: 160 x 5 (row major format) */ +real_t W[ 800 ]; -/** Matrix of size: 4 x 4 (row major format) */ -real_t WN[ 16 ]; +/** Matrix of size: 3 x 3 (row major format) */ +real_t WN[ 9 ]; /** Column vector of size: 4 * @@ -157,56 +157,77 @@ typedef struct ACADOworkspace_ { real_t rk_ttt; -/** Row vector of size: 37 */ -real_t rk_xxx[ 37 ]; +/** Row vector of size: 32 */ +real_t rk_xxx[ 32 ]; -/** Matrix of size: 4 x 24 (row major format) */ -real_t rk_kkk[ 96 ]; +/** Matrix of size: 4 x 28 (row major format) */ +real_t rk_kkk[ 112 ]; -/** Row vector of size: 37 */ -real_t state[ 37 ]; +/** Row vector of size: 32 */ +real_t state[ 32 ]; -/** Column vector of size: 80 */ -real_t d[ 80 ]; +/** Column vector of size: 128 */ +real_t d[ 128 ]; -/** Column vector of size: 100 */ -real_t Dy[ 100 ]; +/** Column vector of size: 160 */ +real_t Dy[ 160 ]; -/** Column vector of size: 4 */ -real_t DyN[ 4 ]; +/** Column vector of size: 3 */ +real_t DyN[ 3 ]; -/** Matrix of size: 80 x 4 (row major format) */ -real_t evGx[ 320 ]; +/** Matrix of size: 128 x 4 (row major format) */ +real_t evGx[ 512 ]; -/** Column vector of size: 80 */ -real_t evGu[ 80 ]; +/** Matrix of size: 128 x 2 (row major format) */ +real_t evGu[ 256 ]; -/** Row vector of size: 17 */ -real_t objValueIn[ 17 ]; +/** Row vector of size: 8 */ +real_t objValueIn[ 8 ]; -/** Row vector of size: 30 */ -real_t objValueOut[ 30 ]; +/** Row vector of size: 5 */ +real_t objValueOut[ 5 ]; -/** Matrix of size: 80 x 4 (row major format) */ -real_t Q1[ 320 ]; +/** Matrix of size: 128 x 4 (row major format) */ +real_t Q1[ 512 ]; -/** Matrix of size: 80 x 5 (row major format) */ -real_t Q2[ 400 ]; +/** Matrix of size: 128 x 5 (row major format) */ +real_t Q2[ 640 ]; -/** Column vector of size: 20 */ -real_t R1[ 20 ]; +/** Matrix of size: 64 x 2 (row major format) */ +real_t R1[ 128 ]; -/** Matrix of size: 20 x 5 (row major format) */ -real_t R2[ 100 ]; +/** Matrix of size: 64 x 5 (row major format) */ +real_t R2[ 320 ]; -/** Column vector of size: 80 */ -real_t S1[ 80 ]; +/** Matrix of size: 128 x 2 (row major format) */ +real_t S1[ 256 ]; /** Matrix of size: 4 x 4 (row major format) */ real_t QN1[ 16 ]; -/** Matrix of size: 4 x 4 (row major format) */ -real_t QN2[ 16 ]; +/** Matrix of size: 4 x 3 (row major format) */ +real_t QN2[ 12 ]; + +/** Column vector of size: 12 */ +real_t conAuxVar[ 12 ]; + +/** Row vector of size: 8 */ +real_t conValueIn[ 8 ]; + +/** Row vector of size: 14 */ +real_t conValueOut[ 14 ]; + +/** Column vector of size: 64 */ +real_t evH[ 64 ]; + +/** Matrix of size: 64 x 4 (row major format) */ +real_t evHx[ 256 ]; + +/** Matrix of size: 64 x 2 (row major format) */ +real_t evHu[ 128 ]; + +/** Column vector of size: 2 */ +real_t evHxd[ 2 ]; /** Column vector of size: 4 */ real_t Dx0[ 4 ]; @@ -214,41 +235,50 @@ real_t Dx0[ 4 ]; /** Matrix of size: 4 x 4 (row major format) */ real_t T[ 16 ]; -/** Column vector of size: 840 */ -real_t E[ 840 ]; +/** Matrix of size: 2112 x 2 (row major format) */ +real_t E[ 4224 ]; -/** Column vector of size: 840 */ -real_t QE[ 840 ]; +/** Matrix of size: 2112 x 2 (row major format) */ +real_t QE[ 4224 ]; -/** Matrix of size: 80 x 4 (row major format) */ -real_t QGx[ 320 ]; +/** Matrix of size: 128 x 4 (row major format) */ +real_t QGx[ 512 ]; -/** Column vector of size: 80 */ -real_t Qd[ 80 ]; +/** Column vector of size: 128 */ +real_t Qd[ 128 ]; -/** Column vector of size: 84 */ -real_t QDy[ 84 ]; +/** Column vector of size: 132 */ +real_t QDy[ 132 ]; -/** Matrix of size: 20 x 4 (row major format) */ -real_t H10[ 80 ]; +/** Matrix of size: 64 x 4 (row major format) */ +real_t H10[ 256 ]; -/** Matrix of size: 24 x 24 (row major format) */ -real_t H[ 576 ]; +/** Matrix of size: 68 x 68 (row major format) */ +real_t H[ 4624 ]; -/** Column vector of size: 24 */ -real_t g[ 24 ]; +/** Matrix of size: 96 x 68 (row major format) */ +real_t A[ 6528 ]; -/** Column vector of size: 24 */ -real_t lb[ 24 ]; +/** Column vector of size: 68 */ +real_t g[ 68 ]; -/** Column vector of size: 24 */ -real_t ub[ 24 ]; +/** Column vector of size: 68 */ +real_t lb[ 68 ]; -/** Column vector of size: 24 */ -real_t x[ 24 ]; +/** Column vector of size: 68 */ +real_t ub[ 68 ]; -/** Column vector of size: 24 */ -real_t y[ 24 ]; +/** Column vector of size: 96 */ +real_t lbA[ 96 ]; + +/** Column vector of size: 96 */ +real_t ubA[ 96 ]; + +/** Column vector of size: 68 */ +real_t x[ 68 ]; + +/** Column vector of size: 164 */ +real_t y[ 164 ]; } ACADOworkspace; @@ -299,7 +329,7 @@ void acado_initializeNodesByForwardSimulation( ); /** Shift differential variables vector by one interval. * - * \param strategy Shifting strategy: 1. Initialize node 21 with xEnd. 2. Initialize node 21 by forward simulation. + * \param strategy Shifting strategy: 1. Initialize node 33 with xEnd. 2. Initialize node 33 by forward simulation. * \param xEnd Value for the x vector on the last node. If =0 the old value is used. * \param uEnd Value for the u vector on the second to last node. If =0 the old value is used. */ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_integrator.c b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_integrator.c new file mode 100644 index 000000000..627f5398f --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_integrator.c @@ -0,0 +1,250 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#include "acado_common.h" + + +void acado_rhs_forw(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 28; + +/* Compute outputs: */ +out[0] = xd[1]; +out[1] = xd[2]; +out[2] = u[0]; +out[3] = u[1]; +out[4] = xd[8]; +out[5] = xd[9]; +out[6] = xd[10]; +out[7] = xd[11]; +out[8] = xd[12]; +out[9] = xd[13]; +out[10] = xd[14]; +out[11] = xd[15]; +out[12] = (real_t)(0.0000000000000000e+00); +out[13] = (real_t)(0.0000000000000000e+00); +out[14] = (real_t)(0.0000000000000000e+00); +out[15] = (real_t)(0.0000000000000000e+00); +out[16] = (real_t)(0.0000000000000000e+00); +out[17] = (real_t)(0.0000000000000000e+00); +out[18] = (real_t)(0.0000000000000000e+00); +out[19] = (real_t)(0.0000000000000000e+00); +out[20] = xd[22]; +out[21] = xd[23]; +out[22] = xd[24]; +out[23] = xd[25]; +out[24] = (real_t)(1.0000000000000000e+00); +out[25] = (real_t)(0.0000000000000000e+00); +out[26] = (real_t)(0.0000000000000000e+00); +out[27] = (real_t)(1.0000000000000000e+00); +} + +/* Fixed step size:0.01 */ +int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ) +{ +int error; + +int run1; +int numSteps[32] = {1, 3, 5, 7, 9, 11, 13, 15, 17, 19, 21, 22, 24, 26, 28, 30, 32, 34, 36, 38, 40, 42, 44, 46, 48, 50, 52, 54, 56, 58, 60, 62}; +int numInts = numSteps[rk_index]; +acadoWorkspace.rk_ttt = 0.0000000000000000e+00; +rk_eta[4] = 1.0000000000000000e+00; +rk_eta[5] = 0.0000000000000000e+00; +rk_eta[6] = 0.0000000000000000e+00; +rk_eta[7] = 0.0000000000000000e+00; +rk_eta[8] = 0.0000000000000000e+00; +rk_eta[9] = 1.0000000000000000e+00; +rk_eta[10] = 0.0000000000000000e+00; +rk_eta[11] = 0.0000000000000000e+00; +rk_eta[12] = 0.0000000000000000e+00; +rk_eta[13] = 0.0000000000000000e+00; +rk_eta[14] = 1.0000000000000000e+00; +rk_eta[15] = 0.0000000000000000e+00; +rk_eta[16] = 0.0000000000000000e+00; +rk_eta[17] = 0.0000000000000000e+00; +rk_eta[18] = 0.0000000000000000e+00; +rk_eta[19] = 1.0000000000000000e+00; +rk_eta[20] = 0.0000000000000000e+00; +rk_eta[21] = 0.0000000000000000e+00; +rk_eta[22] = 0.0000000000000000e+00; +rk_eta[23] = 0.0000000000000000e+00; +rk_eta[24] = 0.0000000000000000e+00; +rk_eta[25] = 0.0000000000000000e+00; +rk_eta[26] = 0.0000000000000000e+00; +rk_eta[27] = 0.0000000000000000e+00; +acadoWorkspace.rk_xxx[28] = rk_eta[28]; +acadoWorkspace.rk_xxx[29] = rk_eta[29]; +acadoWorkspace.rk_xxx[30] = rk_eta[30]; +acadoWorkspace.rk_xxx[31] = rk_eta[31]; + +for (run1 = 0; run1 < 1; ++run1) +{ +for(run1 = 0; run1 < numInts; run1++ ) { +acadoWorkspace.rk_xxx[0] = + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + rk_eta[27]; +acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); +acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[0] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[1] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[2] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[3] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[4] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[5] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[6] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[7] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[8] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[9] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[10] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[11] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[12] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[13] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[14] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[15] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[16] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[17] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[18] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[19] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[20] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[21] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[22] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[23] + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[24] + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[25] + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[26] + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[27] + rk_eta[27]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 28 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[28] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[29] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[30] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[31] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[32] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[33] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[34] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[35] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[36] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[37] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[38] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[39] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[40] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[41] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[42] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[43] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[44] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[45] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[46] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[47] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[48] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[49] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[50] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[51] + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[52] + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[53] + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[54] + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[55] + rk_eta[27]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 56 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[56] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[57] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[58] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[59] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[60] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[61] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[62] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[63] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[64] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[65] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[66] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[67] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[68] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[69] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[70] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[71] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[72] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[73] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[74] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[75] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[76] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[77] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[78] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[79] + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[80] + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[81] + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[82] + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[83] + rk_eta[27]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 84 ]) ); +rk_eta[0] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[0] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[28] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[56] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[84]; +rk_eta[1] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[1] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[29] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[57] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[85]; +rk_eta[2] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[2] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[30] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[58] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[86]; +rk_eta[3] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[3] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[31] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[59] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[87]; +rk_eta[4] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[4] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[32] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[60] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[88]; +rk_eta[5] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[5] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[33] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[61] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[89]; +rk_eta[6] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[6] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[34] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[62] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[90]; +rk_eta[7] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[7] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[35] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[63] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[91]; +rk_eta[8] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[8] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[36] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[64] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[92]; +rk_eta[9] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[9] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[37] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[65] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[93]; +rk_eta[10] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[10] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[38] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[66] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[94]; +rk_eta[11] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[11] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[39] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[67] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[95]; +rk_eta[12] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[12] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[40] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[68] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[96]; +rk_eta[13] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[13] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[41] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[69] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[97]; +rk_eta[14] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[14] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[42] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[70] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[98]; +rk_eta[15] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[15] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[43] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[71] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[99]; +rk_eta[16] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[16] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[44] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[72] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[100]; +rk_eta[17] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[17] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[45] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[73] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[101]; +rk_eta[18] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[18] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[46] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[74] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[102]; +rk_eta[19] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[19] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[47] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[75] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[103]; +rk_eta[20] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[20] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[48] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[76] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[104]; +rk_eta[21] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[21] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[49] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[77] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[105]; +rk_eta[22] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[22] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[50] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[78] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[106]; +rk_eta[23] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[23] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[51] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[79] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[107]; +rk_eta[24] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[24] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[52] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[80] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[108]; +rk_eta[25] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[25] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[53] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[81] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[109]; +rk_eta[26] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[26] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[54] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[82] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[110]; +rk_eta[27] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[27] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[55] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[83] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[111]; +acadoWorkspace.rk_ttt += 1.0000000000000000e+00; +} +} +error = 0; +return error; +} + diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_qpoases_interface.cpp b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_qpoases_interface.cpp similarity index 90% rename from selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_qpoases_interface.cpp rename to selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_qpoases_interface.cpp index dd6fada46..1c468288e 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_qpoases_interface.cpp +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_qpoases_interface.cpp @@ -22,7 +22,7 @@ extern "C" #include "acado_common.h" } -#include "INCLUDE/QProblemB.hpp" +#include "INCLUDE/QProblem.hpp" #if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 #include "INCLUDE/EXTRAS/SolutionAnalysis.hpp" @@ -40,9 +40,9 @@ int acado_solve( void ) { acado_nWSR = QPOASES_NWSRMAX; - QProblemB qp( 24 ); + QProblem qp(68, 96); - returnValue retVal = qp.init(acadoWorkspace.H, acadoWorkspace.g, acadoWorkspace.lb, acadoWorkspace.ub, acado_nWSR, acadoWorkspace.y); + returnValue retVal = qp.init(acadoWorkspace.H, acadoWorkspace.g, acadoWorkspace.A, acadoWorkspace.lb, acadoWorkspace.ub, acadoWorkspace.lbA, acadoWorkspace.ubA, acado_nWSR, acadoWorkspace.y); qp.getPrimalSolution( acadoWorkspace.x ); qp.getDualSolution( acadoWorkspace.y ); diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_qpoases_interface.hpp similarity index 95% rename from selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_qpoases_interface.hpp rename to selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_qpoases_interface.hpp index cc7d1e1c0..cad2ee200 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_qpoases_interface.hpp +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_qpoases_interface.hpp @@ -37,11 +37,11 @@ */ /** Maximum number of optimization variables. */ -#define QPOASES_NVMAX 24 +#define QPOASES_NVMAX 68 /** Maximum number of constraints. */ -#define QPOASES_NCMAX 0 +#define QPOASES_NCMAX 96 /** Maximum number of working set recalculations. */ -#define QPOASES_NWSRMAX 500 +#define QPOASES_NWSRMAX 50 /** Print level for qpOASES. */ #define QPOASES_PRINTLEVEL PL_NONE /** The value of EPS */ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_solver.c b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_solver.c new file mode 100644 index 000000000..4cd0613bf --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/lib_mpc_export/acado_solver.c @@ -0,0 +1,1932 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * + */ + + +#include "acado_common.h" + + + + +/******************************************************************************/ +/* */ +/* ACADO code generation */ +/* */ +/******************************************************************************/ + + +int acado_modelSimulation( ) +{ +int ret; + +int lRun1; +ret = 0; +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +acadoWorkspace.state[0] = acadoVariables.x[lRun1 * 4]; +acadoWorkspace.state[1] = acadoVariables.x[lRun1 * 4 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[lRun1 * 4 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[lRun1 * 4 + 3]; + +acadoWorkspace.state[28] = acadoVariables.u[lRun1 * 2]; +acadoWorkspace.state[29] = acadoVariables.u[lRun1 * 2 + 1]; +acadoWorkspace.state[30] = acadoVariables.od[lRun1 * 2]; +acadoWorkspace.state[31] = acadoVariables.od[lRun1 * 2 + 1]; + +ret = acado_integrate(acadoWorkspace.state, 1, lRun1); + +acadoWorkspace.d[lRun1 * 4] = acadoWorkspace.state[0] - acadoVariables.x[lRun1 * 4 + 4]; +acadoWorkspace.d[lRun1 * 4 + 1] = acadoWorkspace.state[1] - acadoVariables.x[lRun1 * 4 + 5]; +acadoWorkspace.d[lRun1 * 4 + 2] = acadoWorkspace.state[2] - acadoVariables.x[lRun1 * 4 + 6]; +acadoWorkspace.d[lRun1 * 4 + 3] = acadoWorkspace.state[3] - acadoVariables.x[lRun1 * 4 + 7]; + +acadoWorkspace.evGx[lRun1 * 16] = acadoWorkspace.state[4]; +acadoWorkspace.evGx[lRun1 * 16 + 1] = acadoWorkspace.state[5]; +acadoWorkspace.evGx[lRun1 * 16 + 2] = acadoWorkspace.state[6]; +acadoWorkspace.evGx[lRun1 * 16 + 3] = acadoWorkspace.state[7]; +acadoWorkspace.evGx[lRun1 * 16 + 4] = acadoWorkspace.state[8]; +acadoWorkspace.evGx[lRun1 * 16 + 5] = acadoWorkspace.state[9]; +acadoWorkspace.evGx[lRun1 * 16 + 6] = acadoWorkspace.state[10]; +acadoWorkspace.evGx[lRun1 * 16 + 7] = acadoWorkspace.state[11]; +acadoWorkspace.evGx[lRun1 * 16 + 8] = acadoWorkspace.state[12]; +acadoWorkspace.evGx[lRun1 * 16 + 9] = acadoWorkspace.state[13]; +acadoWorkspace.evGx[lRun1 * 16 + 10] = acadoWorkspace.state[14]; +acadoWorkspace.evGx[lRun1 * 16 + 11] = acadoWorkspace.state[15]; +acadoWorkspace.evGx[lRun1 * 16 + 12] = acadoWorkspace.state[16]; +acadoWorkspace.evGx[lRun1 * 16 + 13] = acadoWorkspace.state[17]; +acadoWorkspace.evGx[lRun1 * 16 + 14] = acadoWorkspace.state[18]; +acadoWorkspace.evGx[lRun1 * 16 + 15] = acadoWorkspace.state[19]; + +acadoWorkspace.evGu[lRun1 * 8] = acadoWorkspace.state[20]; +acadoWorkspace.evGu[lRun1 * 8 + 1] = acadoWorkspace.state[21]; +acadoWorkspace.evGu[lRun1 * 8 + 2] = acadoWorkspace.state[22]; +acadoWorkspace.evGu[lRun1 * 8 + 3] = acadoWorkspace.state[23]; +acadoWorkspace.evGu[lRun1 * 8 + 4] = acadoWorkspace.state[24]; +acadoWorkspace.evGu[lRun1 * 8 + 5] = acadoWorkspace.state[25]; +acadoWorkspace.evGu[lRun1 * 8 + 6] = acadoWorkspace.state[26]; +acadoWorkspace.evGu[lRun1 * 8 + 7] = acadoWorkspace.state[27]; +} +return ret; +} + +void acado_evaluateLSQ(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 4; + +/* Compute outputs: */ +out[0] = xd[0]; +out[1] = xd[1]; +out[2] = xd[2]; +out[3] = u[0]; +out[4] = u[1]; +} + +void acado_evaluateLSQEndTerm(const real_t* in, real_t* out) +{ +const real_t* xd = in; + +/* Compute outputs: */ +out[0] = xd[0]; +out[1] = xd[1]; +out[2] = xd[2]; +} + +void acado_setObjQ1Q2( real_t* const tmpObjS, real_t* const tmpQ1, real_t* const tmpQ2 ) +{ +tmpQ2[0] = +tmpObjS[0]; +tmpQ2[1] = +tmpObjS[1]; +tmpQ2[2] = +tmpObjS[2]; +tmpQ2[3] = +tmpObjS[3]; +tmpQ2[4] = +tmpObjS[4]; +tmpQ2[5] = +tmpObjS[5]; +tmpQ2[6] = +tmpObjS[6]; +tmpQ2[7] = +tmpObjS[7]; +tmpQ2[8] = +tmpObjS[8]; +tmpQ2[9] = +tmpObjS[9]; +tmpQ2[10] = +tmpObjS[10]; +tmpQ2[11] = +tmpObjS[11]; +tmpQ2[12] = +tmpObjS[12]; +tmpQ2[13] = +tmpObjS[13]; +tmpQ2[14] = +tmpObjS[14]; +tmpQ2[15] = 0.0; +; +tmpQ2[16] = 0.0; +; +tmpQ2[17] = 0.0; +; +tmpQ2[18] = 0.0; +; +tmpQ2[19] = 0.0; +; +tmpQ1[0] = + tmpQ2[0]; +tmpQ1[1] = + tmpQ2[1]; +tmpQ1[2] = + tmpQ2[2]; +tmpQ1[3] = 0.0; +; +tmpQ1[4] = + tmpQ2[5]; +tmpQ1[5] = + tmpQ2[6]; +tmpQ1[6] = + tmpQ2[7]; +tmpQ1[7] = 0.0; +; +tmpQ1[8] = + tmpQ2[10]; +tmpQ1[9] = + tmpQ2[11]; +tmpQ1[10] = + tmpQ2[12]; +tmpQ1[11] = 0.0; +; +tmpQ1[12] = + tmpQ2[15]; +tmpQ1[13] = + tmpQ2[16]; +tmpQ1[14] = + tmpQ2[17]; +tmpQ1[15] = 0.0; +; +} + +void acado_setObjR1R2( real_t* const tmpObjS, real_t* const tmpR1, real_t* const tmpR2 ) +{ +tmpR2[0] = +tmpObjS[15]; +tmpR2[1] = +tmpObjS[16]; +tmpR2[2] = +tmpObjS[17]; +tmpR2[3] = +tmpObjS[18]; +tmpR2[4] = +tmpObjS[19]; +tmpR2[5] = +tmpObjS[20]; +tmpR2[6] = +tmpObjS[21]; +tmpR2[7] = +tmpObjS[22]; +tmpR2[8] = +tmpObjS[23]; +tmpR2[9] = +tmpObjS[24]; +tmpR1[0] = + tmpR2[3]; +tmpR1[1] = + tmpR2[4]; +tmpR1[2] = + tmpR2[8]; +tmpR1[3] = + tmpR2[9]; +} + +void acado_setObjQN1QN2( real_t* const tmpObjSEndTerm, real_t* const tmpQN1, real_t* const tmpQN2 ) +{ +tmpQN2[0] = +tmpObjSEndTerm[0]; +tmpQN2[1] = +tmpObjSEndTerm[1]; +tmpQN2[2] = +tmpObjSEndTerm[2]; +tmpQN2[3] = +tmpObjSEndTerm[3]; +tmpQN2[4] = +tmpObjSEndTerm[4]; +tmpQN2[5] = +tmpObjSEndTerm[5]; +tmpQN2[6] = +tmpObjSEndTerm[6]; +tmpQN2[7] = +tmpObjSEndTerm[7]; +tmpQN2[8] = +tmpObjSEndTerm[8]; +tmpQN2[9] = 0.0; +; +tmpQN2[10] = 0.0; +; +tmpQN2[11] = 0.0; +; +tmpQN1[0] = + tmpQN2[0]; +tmpQN1[1] = + tmpQN2[1]; +tmpQN1[2] = + tmpQN2[2]; +tmpQN1[3] = 0.0; +; +tmpQN1[4] = + tmpQN2[3]; +tmpQN1[5] = + tmpQN2[4]; +tmpQN1[6] = + tmpQN2[5]; +tmpQN1[7] = 0.0; +; +tmpQN1[8] = + tmpQN2[6]; +tmpQN1[9] = + tmpQN2[7]; +tmpQN1[10] = + tmpQN2[8]; +tmpQN1[11] = 0.0; +; +tmpQN1[12] = + tmpQN2[9]; +tmpQN1[13] = + tmpQN2[10]; +tmpQN1[14] = + tmpQN2[11]; +tmpQN1[15] = 0.0; +; +} + +void acado_evaluateObjective( ) +{ +int runObj; +for (runObj = 0; runObj < 32; ++runObj) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[runObj * 4]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[runObj * 4 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[runObj * 4 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[runObj * 4 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.u[runObj * 2]; +acadoWorkspace.objValueIn[5] = acadoVariables.u[runObj * 2 + 1]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[runObj * 2]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj * 2 + 1]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.Dy[runObj * 5] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.Dy[runObj * 5 + 1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.Dy[runObj * 5 + 2] = acadoWorkspace.objValueOut[2]; +acadoWorkspace.Dy[runObj * 5 + 3] = acadoWorkspace.objValueOut[3]; +acadoWorkspace.Dy[runObj * 5 + 4] = acadoWorkspace.objValueOut[4]; + +acado_setObjQ1Q2( &(acadoVariables.W[ runObj * 25 ]), &(acadoWorkspace.Q1[ runObj * 16 ]), &(acadoWorkspace.Q2[ runObj * 20 ]) ); + +acado_setObjR1R2( &(acadoVariables.W[ runObj * 25 ]), &(acadoWorkspace.R1[ runObj * 4 ]), &(acadoWorkspace.R2[ runObj * 10 ]) ); + +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[128]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[129]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[130]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[131]; +acadoWorkspace.objValueIn[4] = acadoVariables.od[64]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[65]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); + +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2]; + +acado_setObjQN1QN2( acadoVariables.WN, acadoWorkspace.QN1, acadoWorkspace.QN2 ); + +} + +void acado_multGxd( real_t* const dOld, real_t* const Gx1, real_t* const dNew ) +{ +dNew[0] += + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; +dNew[1] += + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; +dNew[2] += + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; +dNew[3] += + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; +} + +void acado_moveGxT( real_t* const Gx1, real_t* const Gx2 ) +{ +Gx2[0] = Gx1[0]; +Gx2[1] = Gx1[1]; +Gx2[2] = Gx1[2]; +Gx2[3] = Gx1[3]; +Gx2[4] = Gx1[4]; +Gx2[5] = Gx1[5]; +Gx2[6] = Gx1[6]; +Gx2[7] = Gx1[7]; +Gx2[8] = Gx1[8]; +Gx2[9] = Gx1[9]; +Gx2[10] = Gx1[10]; +Gx2[11] = Gx1[11]; +Gx2[12] = Gx1[12]; +Gx2[13] = Gx1[13]; +Gx2[14] = Gx1[14]; +Gx2[15] = Gx1[15]; +} + +void acado_multGxGx( real_t* const Gx1, real_t* const Gx2, real_t* const Gx3 ) +{ +Gx3[0] = + Gx1[0]*Gx2[0] + Gx1[1]*Gx2[4] + Gx1[2]*Gx2[8] + Gx1[3]*Gx2[12]; +Gx3[1] = + Gx1[0]*Gx2[1] + Gx1[1]*Gx2[5] + Gx1[2]*Gx2[9] + Gx1[3]*Gx2[13]; +Gx3[2] = + Gx1[0]*Gx2[2] + Gx1[1]*Gx2[6] + Gx1[2]*Gx2[10] + Gx1[3]*Gx2[14]; +Gx3[3] = + Gx1[0]*Gx2[3] + Gx1[1]*Gx2[7] + Gx1[2]*Gx2[11] + Gx1[3]*Gx2[15]; +Gx3[4] = + Gx1[4]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[6]*Gx2[8] + Gx1[7]*Gx2[12]; +Gx3[5] = + Gx1[4]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[6]*Gx2[9] + Gx1[7]*Gx2[13]; +Gx3[6] = + Gx1[4]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[6]*Gx2[10] + Gx1[7]*Gx2[14]; +Gx3[7] = + Gx1[4]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[6]*Gx2[11] + Gx1[7]*Gx2[15]; +Gx3[8] = + Gx1[8]*Gx2[0] + Gx1[9]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[11]*Gx2[12]; +Gx3[9] = + Gx1[8]*Gx2[1] + Gx1[9]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[11]*Gx2[13]; +Gx3[10] = + Gx1[8]*Gx2[2] + Gx1[9]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[11]*Gx2[14]; +Gx3[11] = + Gx1[8]*Gx2[3] + Gx1[9]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[11]*Gx2[15]; +Gx3[12] = + Gx1[12]*Gx2[0] + Gx1[13]*Gx2[4] + Gx1[14]*Gx2[8] + Gx1[15]*Gx2[12]; +Gx3[13] = + Gx1[12]*Gx2[1] + Gx1[13]*Gx2[5] + Gx1[14]*Gx2[9] + Gx1[15]*Gx2[13]; +Gx3[14] = + Gx1[12]*Gx2[2] + Gx1[13]*Gx2[6] + Gx1[14]*Gx2[10] + Gx1[15]*Gx2[14]; +Gx3[15] = + Gx1[12]*Gx2[3] + Gx1[13]*Gx2[7] + Gx1[14]*Gx2[11] + Gx1[15]*Gx2[15]; +} + +void acado_multGxGu( real_t* const Gx1, real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = + Gx1[0]*Gu1[0] + Gx1[1]*Gu1[2] + Gx1[2]*Gu1[4] + Gx1[3]*Gu1[6]; +Gu2[1] = + Gx1[0]*Gu1[1] + Gx1[1]*Gu1[3] + Gx1[2]*Gu1[5] + Gx1[3]*Gu1[7]; +Gu2[2] = + Gx1[4]*Gu1[0] + Gx1[5]*Gu1[2] + Gx1[6]*Gu1[4] + Gx1[7]*Gu1[6]; +Gu2[3] = + Gx1[4]*Gu1[1] + Gx1[5]*Gu1[3] + Gx1[6]*Gu1[5] + Gx1[7]*Gu1[7]; +Gu2[4] = + Gx1[8]*Gu1[0] + Gx1[9]*Gu1[2] + Gx1[10]*Gu1[4] + Gx1[11]*Gu1[6]; +Gu2[5] = + Gx1[8]*Gu1[1] + Gx1[9]*Gu1[3] + Gx1[10]*Gu1[5] + Gx1[11]*Gu1[7]; +Gu2[6] = + Gx1[12]*Gu1[0] + Gx1[13]*Gu1[2] + Gx1[14]*Gu1[4] + Gx1[15]*Gu1[6]; +Gu2[7] = + Gx1[12]*Gu1[1] + Gx1[13]*Gu1[3] + Gx1[14]*Gu1[5] + Gx1[15]*Gu1[7]; +} + +void acado_moveGuE( real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = Gu1[0]; +Gu2[1] = Gu1[1]; +Gu2[2] = Gu1[2]; +Gu2[3] = Gu1[3]; +Gu2[4] = Gu1[4]; +Gu2[5] = Gu1[5]; +Gu2[6] = Gu1[6]; +Gu2[7] = Gu1[7]; +} + +void acado_setBlockH11( int iRow, int iCol, real_t* const Gu1, real_t* const Gu2 ) +{ +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 4)] += + Gu1[0]*Gu2[0] + Gu1[2]*Gu2[2] + Gu1[4]*Gu2[4] + Gu1[6]*Gu2[6]; +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 5)] += + Gu1[0]*Gu2[1] + Gu1[2]*Gu2[3] + Gu1[4]*Gu2[5] + Gu1[6]*Gu2[7]; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 4)] += + Gu1[1]*Gu2[0] + Gu1[3]*Gu2[2] + Gu1[5]*Gu2[4] + Gu1[7]*Gu2[6]; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 5)] += + Gu1[1]*Gu2[1] + Gu1[3]*Gu2[3] + Gu1[5]*Gu2[5] + Gu1[7]*Gu2[7]; +} + +void acado_setBlockH11_R1( int iRow, int iCol, real_t* const R11 ) +{ +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 4)] = R11[0]; +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 5)] = R11[1]; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 4)] = R11[2]; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 5)] = R11[3]; +} + +void acado_zeroBlockH11( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 4)] = 0.0000000000000000e+00; +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 5)] = 0.0000000000000000e+00; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 4)] = 0.0000000000000000e+00; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 5)] = 0.0000000000000000e+00; +} + +void acado_copyHTH( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 4)] = acadoWorkspace.H[(iCol * 136 + 272) + (iRow * 2 + 4)]; +acadoWorkspace.H[(iRow * 136 + 272) + (iCol * 2 + 5)] = acadoWorkspace.H[(iCol * 136 + 340) + (iRow * 2 + 4)]; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 4)] = acadoWorkspace.H[(iCol * 136 + 272) + (iRow * 2 + 5)]; +acadoWorkspace.H[(iRow * 136 + 340) + (iCol * 2 + 5)] = acadoWorkspace.H[(iCol * 136 + 340) + (iRow * 2 + 5)]; +} + +void acado_multQ1d( real_t* const Gx1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; +dNew[1] = + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; +dNew[2] = + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; +dNew[3] = + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; +} + +void acado_multQN1d( real_t* const QN1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + acadoWorkspace.QN1[0]*dOld[0] + acadoWorkspace.QN1[1]*dOld[1] + acadoWorkspace.QN1[2]*dOld[2] + acadoWorkspace.QN1[3]*dOld[3]; +dNew[1] = + acadoWorkspace.QN1[4]*dOld[0] + acadoWorkspace.QN1[5]*dOld[1] + acadoWorkspace.QN1[6]*dOld[2] + acadoWorkspace.QN1[7]*dOld[3]; +dNew[2] = + acadoWorkspace.QN1[8]*dOld[0] + acadoWorkspace.QN1[9]*dOld[1] + acadoWorkspace.QN1[10]*dOld[2] + acadoWorkspace.QN1[11]*dOld[3]; +dNew[3] = + acadoWorkspace.QN1[12]*dOld[0] + acadoWorkspace.QN1[13]*dOld[1] + acadoWorkspace.QN1[14]*dOld[2] + acadoWorkspace.QN1[15]*dOld[3]; +} + +void acado_multRDy( real_t* const R2, real_t* const Dy1, real_t* const RDy1 ) +{ +RDy1[0] = + R2[0]*Dy1[0] + R2[1]*Dy1[1] + R2[2]*Dy1[2] + R2[3]*Dy1[3] + R2[4]*Dy1[4]; +RDy1[1] = + R2[5]*Dy1[0] + R2[6]*Dy1[1] + R2[7]*Dy1[2] + R2[8]*Dy1[3] + R2[9]*Dy1[4]; +} + +void acado_multQDy( real_t* const Q2, real_t* const Dy1, real_t* const QDy1 ) +{ +QDy1[0] = + Q2[0]*Dy1[0] + Q2[1]*Dy1[1] + Q2[2]*Dy1[2] + Q2[3]*Dy1[3] + Q2[4]*Dy1[4]; +QDy1[1] = + Q2[5]*Dy1[0] + Q2[6]*Dy1[1] + Q2[7]*Dy1[2] + Q2[8]*Dy1[3] + Q2[9]*Dy1[4]; +QDy1[2] = + Q2[10]*Dy1[0] + Q2[11]*Dy1[1] + Q2[12]*Dy1[2] + Q2[13]*Dy1[3] + Q2[14]*Dy1[4]; +QDy1[3] = + Q2[15]*Dy1[0] + Q2[16]*Dy1[1] + Q2[17]*Dy1[2] + Q2[18]*Dy1[3] + Q2[19]*Dy1[4]; +} + +void acado_multEQDy( real_t* const E1, real_t* const QDy1, real_t* const U1 ) +{ +U1[0] += + E1[0]*QDy1[0] + E1[2]*QDy1[1] + E1[4]*QDy1[2] + E1[6]*QDy1[3]; +U1[1] += + E1[1]*QDy1[0] + E1[3]*QDy1[1] + E1[5]*QDy1[2] + E1[7]*QDy1[3]; +} + +void acado_multQETGx( real_t* const E1, real_t* const Gx1, real_t* const H101 ) +{ +H101[0] += + E1[0]*Gx1[0] + E1[2]*Gx1[4] + E1[4]*Gx1[8] + E1[6]*Gx1[12]; +H101[1] += + E1[0]*Gx1[1] + E1[2]*Gx1[5] + E1[4]*Gx1[9] + E1[6]*Gx1[13]; +H101[2] += + E1[0]*Gx1[2] + E1[2]*Gx1[6] + E1[4]*Gx1[10] + E1[6]*Gx1[14]; +H101[3] += + E1[0]*Gx1[3] + E1[2]*Gx1[7] + E1[4]*Gx1[11] + E1[6]*Gx1[15]; +H101[4] += + E1[1]*Gx1[0] + E1[3]*Gx1[4] + E1[5]*Gx1[8] + E1[7]*Gx1[12]; +H101[5] += + E1[1]*Gx1[1] + E1[3]*Gx1[5] + E1[5]*Gx1[9] + E1[7]*Gx1[13]; +H101[6] += + E1[1]*Gx1[2] + E1[3]*Gx1[6] + E1[5]*Gx1[10] + E1[7]*Gx1[14]; +H101[7] += + E1[1]*Gx1[3] + E1[3]*Gx1[7] + E1[5]*Gx1[11] + E1[7]*Gx1[15]; +} + +void acado_zeroBlockH10( real_t* const H101 ) +{ +{ int lCopy; for (lCopy = 0; lCopy < 8; lCopy++) H101[ lCopy ] = 0; } +} + +void acado_multEDu( real_t* const E1, real_t* const U1, real_t* const dNew ) +{ +dNew[0] += + E1[0]*U1[0] + E1[1]*U1[1]; +dNew[1] += + E1[2]*U1[0] + E1[3]*U1[1]; +dNew[2] += + E1[4]*U1[0] + E1[5]*U1[1]; +dNew[3] += + E1[6]*U1[0] + E1[7]*U1[1]; +} + +void acado_zeroBlockH00( ) +{ +acadoWorkspace.H[0] = 0.0000000000000000e+00; +acadoWorkspace.H[1] = 0.0000000000000000e+00; +acadoWorkspace.H[2] = 0.0000000000000000e+00; +acadoWorkspace.H[3] = 0.0000000000000000e+00; +acadoWorkspace.H[68] = 0.0000000000000000e+00; +acadoWorkspace.H[69] = 0.0000000000000000e+00; +acadoWorkspace.H[70] = 0.0000000000000000e+00; +acadoWorkspace.H[71] = 0.0000000000000000e+00; +acadoWorkspace.H[136] = 0.0000000000000000e+00; +acadoWorkspace.H[137] = 0.0000000000000000e+00; +acadoWorkspace.H[138] = 0.0000000000000000e+00; +acadoWorkspace.H[139] = 0.0000000000000000e+00; +acadoWorkspace.H[204] = 0.0000000000000000e+00; +acadoWorkspace.H[205] = 0.0000000000000000e+00; +acadoWorkspace.H[206] = 0.0000000000000000e+00; +acadoWorkspace.H[207] = 0.0000000000000000e+00; +} + +void acado_multCTQC( real_t* const Gx1, real_t* const Gx2 ) +{ +acadoWorkspace.H[0] += + Gx1[0]*Gx2[0] + Gx1[4]*Gx2[4] + Gx1[8]*Gx2[8] + Gx1[12]*Gx2[12]; +acadoWorkspace.H[1] += + Gx1[0]*Gx2[1] + Gx1[4]*Gx2[5] + Gx1[8]*Gx2[9] + Gx1[12]*Gx2[13]; +acadoWorkspace.H[2] += + Gx1[0]*Gx2[2] + Gx1[4]*Gx2[6] + Gx1[8]*Gx2[10] + Gx1[12]*Gx2[14]; +acadoWorkspace.H[3] += + Gx1[0]*Gx2[3] + Gx1[4]*Gx2[7] + Gx1[8]*Gx2[11] + Gx1[12]*Gx2[15]; +acadoWorkspace.H[68] += + Gx1[1]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[9]*Gx2[8] + Gx1[13]*Gx2[12]; +acadoWorkspace.H[69] += + Gx1[1]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[9]*Gx2[9] + Gx1[13]*Gx2[13]; +acadoWorkspace.H[70] += + Gx1[1]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[9]*Gx2[10] + Gx1[13]*Gx2[14]; +acadoWorkspace.H[71] += + Gx1[1]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[9]*Gx2[11] + Gx1[13]*Gx2[15]; +acadoWorkspace.H[136] += + Gx1[2]*Gx2[0] + Gx1[6]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[14]*Gx2[12]; +acadoWorkspace.H[137] += + Gx1[2]*Gx2[1] + Gx1[6]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[14]*Gx2[13]; +acadoWorkspace.H[138] += + Gx1[2]*Gx2[2] + Gx1[6]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[14]*Gx2[14]; +acadoWorkspace.H[139] += + Gx1[2]*Gx2[3] + Gx1[6]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[14]*Gx2[15]; +acadoWorkspace.H[204] += + Gx1[3]*Gx2[0] + Gx1[7]*Gx2[4] + Gx1[11]*Gx2[8] + Gx1[15]*Gx2[12]; +acadoWorkspace.H[205] += + Gx1[3]*Gx2[1] + Gx1[7]*Gx2[5] + Gx1[11]*Gx2[9] + Gx1[15]*Gx2[13]; +acadoWorkspace.H[206] += + Gx1[3]*Gx2[2] + Gx1[7]*Gx2[6] + Gx1[11]*Gx2[10] + Gx1[15]*Gx2[14]; +acadoWorkspace.H[207] += + Gx1[3]*Gx2[3] + Gx1[7]*Gx2[7] + Gx1[11]*Gx2[11] + Gx1[15]*Gx2[15]; +} + +void acado_multHxC( real_t* const Hx, real_t* const Gx, real_t* const A01 ) +{ +A01[0] = + Hx[0]*Gx[0] + Hx[1]*Gx[4] + Hx[2]*Gx[8] + Hx[3]*Gx[12]; +A01[1] = + Hx[0]*Gx[1] + Hx[1]*Gx[5] + Hx[2]*Gx[9] + Hx[3]*Gx[13]; +A01[2] = + Hx[0]*Gx[2] + Hx[1]*Gx[6] + Hx[2]*Gx[10] + Hx[3]*Gx[14]; +A01[3] = + Hx[0]*Gx[3] + Hx[1]*Gx[7] + Hx[2]*Gx[11] + Hx[3]*Gx[15]; +A01[68] = + Hx[4]*Gx[0] + Hx[5]*Gx[4] + Hx[6]*Gx[8] + Hx[7]*Gx[12]; +A01[69] = + Hx[4]*Gx[1] + Hx[5]*Gx[5] + Hx[6]*Gx[9] + Hx[7]*Gx[13]; +A01[70] = + Hx[4]*Gx[2] + Hx[5]*Gx[6] + Hx[6]*Gx[10] + Hx[7]*Gx[14]; +A01[71] = + Hx[4]*Gx[3] + Hx[5]*Gx[7] + Hx[6]*Gx[11] + Hx[7]*Gx[15]; +} + +void acado_multHxE( real_t* const Hx, real_t* const E, int row, int col ) +{ +acadoWorkspace.A[(row * 136 + 2176) + (col * 2 + 4)] = + Hx[0]*E[0] + Hx[1]*E[2] + Hx[2]*E[4] + Hx[3]*E[6]; +acadoWorkspace.A[(row * 136 + 2176) + (col * 2 + 5)] = + Hx[0]*E[1] + Hx[1]*E[3] + Hx[2]*E[5] + Hx[3]*E[7]; +acadoWorkspace.A[(row * 136 + 2244) + (col * 2 + 4)] = + Hx[4]*E[0] + Hx[5]*E[2] + Hx[6]*E[4] + Hx[7]*E[6]; +acadoWorkspace.A[(row * 136 + 2244) + (col * 2 + 5)] = + Hx[4]*E[1] + Hx[5]*E[3] + Hx[6]*E[5] + Hx[7]*E[7]; +} + +void acado_macHxd( real_t* const Hx, real_t* const tmpd, real_t* const lbA, real_t* const ubA ) +{ +acadoWorkspace.evHxd[0] = + Hx[0]*tmpd[0] + Hx[1]*tmpd[1] + Hx[2]*tmpd[2] + Hx[3]*tmpd[3]; +acadoWorkspace.evHxd[1] = + Hx[4]*tmpd[0] + Hx[5]*tmpd[1] + Hx[6]*tmpd[2] + Hx[7]*tmpd[3]; +lbA[0] -= acadoWorkspace.evHxd[0]; +lbA[1] -= acadoWorkspace.evHxd[1]; +ubA[0] -= acadoWorkspace.evHxd[0]; +ubA[1] -= acadoWorkspace.evHxd[1]; +} + +void acado_evaluatePathConstraints(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 4; +const real_t* od = in + 6; +/* Vector of auxiliary variables; number of elements: 12. */ +real_t* a = acadoWorkspace.conAuxVar; + +/* Compute intermediate quantities: */ +a[0] = (real_t)(0.0000000000000000e+00); +a[1] = (real_t)(0.0000000000000000e+00); +a[2] = (real_t)(1.0000000000000000e+00); +a[3] = (real_t)(0.0000000000000000e+00); +a[4] = (real_t)(0.0000000000000000e+00); +a[5] = (real_t)(0.0000000000000000e+00); +a[6] = (real_t)(1.0000000000000000e+00); +a[7] = (real_t)(0.0000000000000000e+00); +a[8] = (real_t)(0.0000000000000000e+00); +a[9] = (real_t)(1.0000000000000000e+00); +a[10] = (real_t)(0.0000000000000000e+00); +a[11] = (real_t)(1.0000000000000000e+00); + +/* Compute outputs: */ +out[0] = ((xd[2]-od[0])+u[1]); +out[1] = ((xd[2]-od[1])+u[1]); +out[2] = a[0]; +out[3] = a[1]; +out[4] = a[2]; +out[5] = a[3]; +out[6] = a[4]; +out[7] = a[5]; +out[8] = a[6]; +out[9] = a[7]; +out[10] = a[8]; +out[11] = a[9]; +out[12] = a[10]; +out[13] = a[11]; +} + +void acado_macCTSlx( real_t* const C0, real_t* const g0 ) +{ +g0[0] += 0.0; +; +g0[1] += 0.0; +; +g0[2] += 0.0; +; +g0[3] += 0.0; +; +} + +void acado_macETSlu( real_t* const E0, real_t* const g1 ) +{ +g1[0] += 0.0; +; +g1[1] += 0.0; +; +} + +void acado_condensePrep( ) +{ +int lRun1; +int lRun2; +int lRun3; +int lRun4; +int lRun5; +/** Row vector of size: 32 */ +static const int xBoundIndices[ 32 ] = +{ 5, 9, 13, 17, 21, 25, 29, 33, 37, 41, 45, 49, 53, 57, 61, 65, 69, 73, 77, 81, 85, 89, 93, 97, 101, 105, 109, 113, 117, 121, 125, 129 }; +acado_moveGuE( acadoWorkspace.evGu, acadoWorkspace.E ); +for (lRun1 = 1; lRun1 < 32; ++lRun1) +{ +acado_moveGxT( &(acadoWorkspace.evGx[ lRun1 * 16 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ lRun1 * 4-4 ]), &(acadoWorkspace.evGx[ lRun1 * 16 ]), &(acadoWorkspace.d[ lRun1 * 4 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ lRun1 * 16-16 ]), &(acadoWorkspace.evGx[ lRun1 * 16 ]) ); +for (lRun2 = 0; lRun2 < lRun1; ++lRun2) +{ +lRun4 = (((lRun1) * (lRun1-1)) / (2)) + (lRun2); +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ lRun4 * 8 ]), &(acadoWorkspace.E[ lRun3 * 8 ]) ); +} +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_moveGuE( &(acadoWorkspace.evGu[ lRun1 * 8 ]), &(acadoWorkspace.E[ lRun3 * 8 ]) ); +} + +acado_multGxGx( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multGxGx( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 320 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 336 ]), &(acadoWorkspace.evGx[ 320 ]), &(acadoWorkspace.QGx[ 320 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 352 ]), &(acadoWorkspace.evGx[ 336 ]), &(acadoWorkspace.QGx[ 336 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 368 ]), &(acadoWorkspace.evGx[ 352 ]), &(acadoWorkspace.QGx[ 352 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 384 ]), &(acadoWorkspace.evGx[ 368 ]), &(acadoWorkspace.QGx[ 368 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 400 ]), &(acadoWorkspace.evGx[ 384 ]), &(acadoWorkspace.QGx[ 384 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 416 ]), &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.QGx[ 400 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.evGx[ 416 ]), &(acadoWorkspace.QGx[ 416 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 448 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.QGx[ 432 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 464 ]), &(acadoWorkspace.evGx[ 448 ]), &(acadoWorkspace.QGx[ 448 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 480 ]), &(acadoWorkspace.evGx[ 464 ]), &(acadoWorkspace.QGx[ 464 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 496 ]), &(acadoWorkspace.evGx[ 480 ]), &(acadoWorkspace.QGx[ 480 ]) ); +acado_multGxGx( acadoWorkspace.QN1, &(acadoWorkspace.evGx[ 496 ]), &(acadoWorkspace.QGx[ 496 ]) ); + +for (lRun1 = 0; lRun1 < 31; ++lRun1) +{ +for (lRun2 = 0; lRun2 < lRun1 + 1; ++lRun2) +{ +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multGxGu( &(acadoWorkspace.Q1[ lRun1 * 16 + 16 ]), &(acadoWorkspace.E[ lRun3 * 8 ]), &(acadoWorkspace.QE[ lRun3 * 8 ]) ); +} +} + +for (lRun2 = 0; lRun2 < lRun1 + 1; ++lRun2) +{ +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ lRun3 * 8 ]), &(acadoWorkspace.QE[ lRun3 * 8 ]) ); +} + +acado_zeroBlockH00( ); +acado_multCTQC( acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multCTQC( &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 320 ]), &(acadoWorkspace.QGx[ 320 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 336 ]), &(acadoWorkspace.QGx[ 336 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 352 ]), &(acadoWorkspace.QGx[ 352 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 368 ]), &(acadoWorkspace.QGx[ 368 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 384 ]), &(acadoWorkspace.QGx[ 384 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.QGx[ 400 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 416 ]), &(acadoWorkspace.QGx[ 416 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.QGx[ 432 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 448 ]), &(acadoWorkspace.QGx[ 448 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 464 ]), &(acadoWorkspace.QGx[ 464 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 480 ]), &(acadoWorkspace.QGx[ 480 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 496 ]), &(acadoWorkspace.QGx[ 496 ]) ); + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +acado_zeroBlockH10( &(acadoWorkspace.H10[ lRun1 * 8 ]) ); +for (lRun2 = lRun1; lRun2 < 32; ++lRun2) +{ +lRun3 = (((lRun2 + 1) * (lRun2)) / (2)) + (lRun1); +acado_multQETGx( &(acadoWorkspace.QE[ lRun3 * 8 ]), &(acadoWorkspace.evGx[ lRun2 * 16 ]), &(acadoWorkspace.H10[ lRun1 * 8 ]) ); +} +} + +for (lRun2 = 0;lRun2 < 4; ++lRun2) +for (lRun3 = 0;lRun3 < 64; ++lRun3) +acadoWorkspace.H[(lRun2 * 68) + (lRun3 + 4)] = acadoWorkspace.H10[(lRun3 * 4) + (lRun2)]; + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +acado_setBlockH11_R1( lRun1, lRun1, &(acadoWorkspace.R1[ lRun1 * 4 ]) ); +lRun2 = lRun1; +for (lRun3 = lRun1; lRun3 < 32; ++lRun3) +{ +lRun4 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun1); +lRun5 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun2); +acado_setBlockH11( lRun1, lRun2, &(acadoWorkspace.E[ lRun4 * 8 ]), &(acadoWorkspace.QE[ lRun5 * 8 ]) ); +} +for (lRun2 = lRun1 + 1; lRun2 < 32; ++lRun2) +{ +acado_zeroBlockH11( lRun1, lRun2 ); +for (lRun3 = lRun2; lRun3 < 32; ++lRun3) +{ +lRun4 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun1); +lRun5 = (((lRun3 + 1) * (lRun3)) / (2)) + (lRun2); +acado_setBlockH11( lRun1, lRun2, &(acadoWorkspace.E[ lRun4 * 8 ]), &(acadoWorkspace.QE[ lRun5 * 8 ]) ); +} +} +} + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +for (lRun2 = 0; lRun2 < lRun1; ++lRun2) +{ +acado_copyHTH( lRun1, lRun2 ); +} +} + +for (lRun2 = 0;lRun2 < 64; ++lRun2) +for (lRun3 = 0;lRun3 < 4; ++lRun3) +acadoWorkspace.H[(lRun2 * 68 + 272) + (lRun3)] = acadoWorkspace.H10[(lRun2 * 4) + (lRun3)]; + +acado_multQ1d( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.d, acadoWorkspace.Qd ); +acado_multQ1d( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.d[ 4 ]), &(acadoWorkspace.Qd[ 4 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.d[ 8 ]), &(acadoWorkspace.Qd[ 8 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.Qd[ 12 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.d[ 16 ]), &(acadoWorkspace.Qd[ 16 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.d[ 20 ]), &(acadoWorkspace.Qd[ 20 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.Qd[ 24 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.d[ 28 ]), &(acadoWorkspace.Qd[ 28 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.d[ 32 ]), &(acadoWorkspace.Qd[ 32 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.Qd[ 36 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.d[ 40 ]), &(acadoWorkspace.Qd[ 40 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.d[ 44 ]), &(acadoWorkspace.Qd[ 44 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.Qd[ 48 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.d[ 52 ]), &(acadoWorkspace.Qd[ 52 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.d[ 56 ]), &(acadoWorkspace.Qd[ 56 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.Qd[ 60 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.d[ 64 ]), &(acadoWorkspace.Qd[ 64 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.d[ 68 ]), &(acadoWorkspace.Qd[ 68 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.Qd[ 72 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 320 ]), &(acadoWorkspace.d[ 76 ]), &(acadoWorkspace.Qd[ 76 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 336 ]), &(acadoWorkspace.d[ 80 ]), &(acadoWorkspace.Qd[ 80 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 352 ]), &(acadoWorkspace.d[ 84 ]), &(acadoWorkspace.Qd[ 84 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 368 ]), &(acadoWorkspace.d[ 88 ]), &(acadoWorkspace.Qd[ 88 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 384 ]), &(acadoWorkspace.d[ 92 ]), &(acadoWorkspace.Qd[ 92 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 400 ]), &(acadoWorkspace.d[ 96 ]), &(acadoWorkspace.Qd[ 96 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 416 ]), &(acadoWorkspace.d[ 100 ]), &(acadoWorkspace.Qd[ 100 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.d[ 104 ]), &(acadoWorkspace.Qd[ 104 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 448 ]), &(acadoWorkspace.d[ 108 ]), &(acadoWorkspace.Qd[ 108 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 464 ]), &(acadoWorkspace.d[ 112 ]), &(acadoWorkspace.Qd[ 112 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 480 ]), &(acadoWorkspace.d[ 116 ]), &(acadoWorkspace.Qd[ 116 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 496 ]), &(acadoWorkspace.d[ 120 ]), &(acadoWorkspace.Qd[ 120 ]) ); +acado_multQN1d( acadoWorkspace.QN1, &(acadoWorkspace.d[ 124 ]), &(acadoWorkspace.Qd[ 124 ]) ); + +acado_macCTSlx( acadoWorkspace.evGx, acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 320 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 336 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 352 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 368 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 384 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 400 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 416 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 432 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 448 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 464 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 480 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 496 ]), acadoWorkspace.g ); +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +for (lRun2 = lRun1; lRun2 < 32; ++lRun2) +{ +lRun3 = (((lRun2 + 1) * (lRun2)) / (2)) + (lRun1); +acado_macETSlu( &(acadoWorkspace.QE[ lRun3 * 8 ]), &(acadoWorkspace.g[ lRun1 * 2 + 4 ]) ); +} +} +acadoWorkspace.lb[4] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[0]; +acadoWorkspace.lb[5] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[1]; +acadoWorkspace.lb[6] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[2]; +acadoWorkspace.lb[7] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[3]; +acadoWorkspace.lb[8] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[4]; +acadoWorkspace.lb[9] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[5]; +acadoWorkspace.lb[10] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[6]; +acadoWorkspace.lb[11] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[7]; +acadoWorkspace.lb[12] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[8]; +acadoWorkspace.lb[13] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[9]; +acadoWorkspace.lb[14] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[10]; +acadoWorkspace.lb[15] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[11]; +acadoWorkspace.lb[16] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[12]; +acadoWorkspace.lb[17] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[13]; +acadoWorkspace.lb[18] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[14]; +acadoWorkspace.lb[19] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[15]; +acadoWorkspace.lb[20] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[16]; +acadoWorkspace.lb[21] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[17]; +acadoWorkspace.lb[22] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[18]; +acadoWorkspace.lb[23] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[19]; +acadoWorkspace.lb[24] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[20]; +acadoWorkspace.lb[25] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[21]; +acadoWorkspace.lb[26] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[22]; +acadoWorkspace.lb[27] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[23]; +acadoWorkspace.lb[28] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[24]; +acadoWorkspace.lb[29] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[25]; +acadoWorkspace.lb[30] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[26]; +acadoWorkspace.lb[31] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[27]; +acadoWorkspace.lb[32] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[28]; +acadoWorkspace.lb[33] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[29]; +acadoWorkspace.lb[34] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[30]; +acadoWorkspace.lb[35] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[31]; +acadoWorkspace.lb[36] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[32]; +acadoWorkspace.lb[37] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[33]; +acadoWorkspace.lb[38] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[34]; +acadoWorkspace.lb[39] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[35]; +acadoWorkspace.lb[40] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[36]; +acadoWorkspace.lb[41] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[37]; +acadoWorkspace.lb[42] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[38]; +acadoWorkspace.lb[43] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[39]; +acadoWorkspace.lb[44] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[40]; +acadoWorkspace.lb[45] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[41]; +acadoWorkspace.lb[46] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[42]; +acadoWorkspace.lb[47] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[43]; +acadoWorkspace.lb[48] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[44]; +acadoWorkspace.lb[49] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[45]; +acadoWorkspace.lb[50] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[46]; +acadoWorkspace.lb[51] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[47]; +acadoWorkspace.lb[52] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[48]; +acadoWorkspace.lb[53] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[49]; +acadoWorkspace.lb[54] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[50]; +acadoWorkspace.lb[55] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[51]; +acadoWorkspace.lb[56] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[52]; +acadoWorkspace.lb[57] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[53]; +acadoWorkspace.lb[58] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[54]; +acadoWorkspace.lb[59] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[55]; +acadoWorkspace.lb[60] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[56]; +acadoWorkspace.lb[61] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[57]; +acadoWorkspace.lb[62] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[58]; +acadoWorkspace.lb[63] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[59]; +acadoWorkspace.lb[64] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[60]; +acadoWorkspace.lb[65] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[61]; +acadoWorkspace.lb[66] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[62]; +acadoWorkspace.lb[67] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[63]; +acadoWorkspace.ub[4] = (real_t)1.0000000000000000e+12 - acadoVariables.u[0]; +acadoWorkspace.ub[5] = (real_t)1.0000000000000000e+12 - acadoVariables.u[1]; +acadoWorkspace.ub[6] = (real_t)1.0000000000000000e+12 - acadoVariables.u[2]; +acadoWorkspace.ub[7] = (real_t)1.0000000000000000e+12 - acadoVariables.u[3]; +acadoWorkspace.ub[8] = (real_t)1.0000000000000000e+12 - acadoVariables.u[4]; +acadoWorkspace.ub[9] = (real_t)1.0000000000000000e+12 - acadoVariables.u[5]; +acadoWorkspace.ub[10] = (real_t)1.0000000000000000e+12 - acadoVariables.u[6]; +acadoWorkspace.ub[11] = (real_t)1.0000000000000000e+12 - acadoVariables.u[7]; +acadoWorkspace.ub[12] = (real_t)1.0000000000000000e+12 - acadoVariables.u[8]; +acadoWorkspace.ub[13] = (real_t)1.0000000000000000e+12 - acadoVariables.u[9]; +acadoWorkspace.ub[14] = (real_t)1.0000000000000000e+12 - acadoVariables.u[10]; +acadoWorkspace.ub[15] = (real_t)1.0000000000000000e+12 - acadoVariables.u[11]; +acadoWorkspace.ub[16] = (real_t)1.0000000000000000e+12 - acadoVariables.u[12]; +acadoWorkspace.ub[17] = (real_t)1.0000000000000000e+12 - acadoVariables.u[13]; +acadoWorkspace.ub[18] = (real_t)1.0000000000000000e+12 - acadoVariables.u[14]; +acadoWorkspace.ub[19] = (real_t)1.0000000000000000e+12 - acadoVariables.u[15]; +acadoWorkspace.ub[20] = (real_t)1.0000000000000000e+12 - acadoVariables.u[16]; +acadoWorkspace.ub[21] = (real_t)1.0000000000000000e+12 - acadoVariables.u[17]; +acadoWorkspace.ub[22] = (real_t)1.0000000000000000e+12 - acadoVariables.u[18]; +acadoWorkspace.ub[23] = (real_t)1.0000000000000000e+12 - acadoVariables.u[19]; +acadoWorkspace.ub[24] = (real_t)1.0000000000000000e+12 - acadoVariables.u[20]; +acadoWorkspace.ub[25] = (real_t)1.0000000000000000e+12 - acadoVariables.u[21]; +acadoWorkspace.ub[26] = (real_t)1.0000000000000000e+12 - acadoVariables.u[22]; +acadoWorkspace.ub[27] = (real_t)1.0000000000000000e+12 - acadoVariables.u[23]; +acadoWorkspace.ub[28] = (real_t)1.0000000000000000e+12 - acadoVariables.u[24]; +acadoWorkspace.ub[29] = (real_t)1.0000000000000000e+12 - acadoVariables.u[25]; +acadoWorkspace.ub[30] = (real_t)1.0000000000000000e+12 - acadoVariables.u[26]; +acadoWorkspace.ub[31] = (real_t)1.0000000000000000e+12 - acadoVariables.u[27]; +acadoWorkspace.ub[32] = (real_t)1.0000000000000000e+12 - acadoVariables.u[28]; +acadoWorkspace.ub[33] = (real_t)1.0000000000000000e+12 - acadoVariables.u[29]; +acadoWorkspace.ub[34] = (real_t)1.0000000000000000e+12 - acadoVariables.u[30]; +acadoWorkspace.ub[35] = (real_t)1.0000000000000000e+12 - acadoVariables.u[31]; +acadoWorkspace.ub[36] = (real_t)1.0000000000000000e+12 - acadoVariables.u[32]; +acadoWorkspace.ub[37] = (real_t)1.0000000000000000e+12 - acadoVariables.u[33]; +acadoWorkspace.ub[38] = (real_t)1.0000000000000000e+12 - acadoVariables.u[34]; +acadoWorkspace.ub[39] = (real_t)1.0000000000000000e+12 - acadoVariables.u[35]; +acadoWorkspace.ub[40] = (real_t)1.0000000000000000e+12 - acadoVariables.u[36]; +acadoWorkspace.ub[41] = (real_t)1.0000000000000000e+12 - acadoVariables.u[37]; +acadoWorkspace.ub[42] = (real_t)1.0000000000000000e+12 - acadoVariables.u[38]; +acadoWorkspace.ub[43] = (real_t)1.0000000000000000e+12 - acadoVariables.u[39]; +acadoWorkspace.ub[44] = (real_t)1.0000000000000000e+12 - acadoVariables.u[40]; +acadoWorkspace.ub[45] = (real_t)1.0000000000000000e+12 - acadoVariables.u[41]; +acadoWorkspace.ub[46] = (real_t)1.0000000000000000e+12 - acadoVariables.u[42]; +acadoWorkspace.ub[47] = (real_t)1.0000000000000000e+12 - acadoVariables.u[43]; +acadoWorkspace.ub[48] = (real_t)1.0000000000000000e+12 - acadoVariables.u[44]; +acadoWorkspace.ub[49] = (real_t)1.0000000000000000e+12 - acadoVariables.u[45]; +acadoWorkspace.ub[50] = (real_t)1.0000000000000000e+12 - acadoVariables.u[46]; +acadoWorkspace.ub[51] = (real_t)1.0000000000000000e+12 - acadoVariables.u[47]; +acadoWorkspace.ub[52] = (real_t)1.0000000000000000e+12 - acadoVariables.u[48]; +acadoWorkspace.ub[53] = (real_t)1.0000000000000000e+12 - acadoVariables.u[49]; +acadoWorkspace.ub[54] = (real_t)1.0000000000000000e+12 - acadoVariables.u[50]; +acadoWorkspace.ub[55] = (real_t)1.0000000000000000e+12 - acadoVariables.u[51]; +acadoWorkspace.ub[56] = (real_t)1.0000000000000000e+12 - acadoVariables.u[52]; +acadoWorkspace.ub[57] = (real_t)1.0000000000000000e+12 - acadoVariables.u[53]; +acadoWorkspace.ub[58] = (real_t)1.0000000000000000e+12 - acadoVariables.u[54]; +acadoWorkspace.ub[59] = (real_t)1.0000000000000000e+12 - acadoVariables.u[55]; +acadoWorkspace.ub[60] = (real_t)1.0000000000000000e+12 - acadoVariables.u[56]; +acadoWorkspace.ub[61] = (real_t)1.0000000000000000e+12 - acadoVariables.u[57]; +acadoWorkspace.ub[62] = (real_t)1.0000000000000000e+12 - acadoVariables.u[58]; +acadoWorkspace.ub[63] = (real_t)1.0000000000000000e+12 - acadoVariables.u[59]; +acadoWorkspace.ub[64] = (real_t)1.0000000000000000e+12 - acadoVariables.u[60]; +acadoWorkspace.ub[65] = (real_t)1.0000000000000000e+12 - acadoVariables.u[61]; +acadoWorkspace.ub[66] = (real_t)1.0000000000000000e+12 - acadoVariables.u[62]; +acadoWorkspace.ub[67] = (real_t)1.0000000000000000e+12 - acadoVariables.u[63]; + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +lRun3 = xBoundIndices[ lRun1 ] - 4; +lRun4 = ((lRun3) / (4)) + (1); +acadoWorkspace.A[lRun1 * 68] = acadoWorkspace.evGx[lRun3 * 4]; +acadoWorkspace.A[lRun1 * 68 + 1] = acadoWorkspace.evGx[lRun3 * 4 + 1]; +acadoWorkspace.A[lRun1 * 68 + 2] = acadoWorkspace.evGx[lRun3 * 4 + 2]; +acadoWorkspace.A[lRun1 * 68 + 3] = acadoWorkspace.evGx[lRun3 * 4 + 3]; +for (lRun2 = 0; lRun2 < lRun4; ++lRun2) +{ +lRun5 = (((((lRun4) * (lRun4-1)) / (2)) + (lRun2)) * (4)) + ((lRun3) % (4)); +acadoWorkspace.A[(lRun1 * 68) + (lRun2 * 2 + 4)] = acadoWorkspace.E[lRun5 * 2]; +acadoWorkspace.A[(lRun1 * 68) + (lRun2 * 2 + 5)] = acadoWorkspace.E[lRun5 * 2 + 1]; +} +} + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +acadoWorkspace.conValueIn[0] = acadoVariables.x[lRun1 * 4]; +acadoWorkspace.conValueIn[1] = acadoVariables.x[lRun1 * 4 + 1]; +acadoWorkspace.conValueIn[2] = acadoVariables.x[lRun1 * 4 + 2]; +acadoWorkspace.conValueIn[3] = acadoVariables.x[lRun1 * 4 + 3]; +acadoWorkspace.conValueIn[4] = acadoVariables.u[lRun1 * 2]; +acadoWorkspace.conValueIn[5] = acadoVariables.u[lRun1 * 2 + 1]; +acadoWorkspace.conValueIn[6] = acadoVariables.od[lRun1 * 2]; +acadoWorkspace.conValueIn[7] = acadoVariables.od[lRun1 * 2 + 1]; +acado_evaluatePathConstraints( acadoWorkspace.conValueIn, acadoWorkspace.conValueOut ); +acadoWorkspace.evH[lRun1 * 2] = acadoWorkspace.conValueOut[0]; +acadoWorkspace.evH[lRun1 * 2 + 1] = acadoWorkspace.conValueOut[1]; + +acadoWorkspace.evHx[lRun1 * 8] = acadoWorkspace.conValueOut[2]; +acadoWorkspace.evHx[lRun1 * 8 + 1] = acadoWorkspace.conValueOut[3]; +acadoWorkspace.evHx[lRun1 * 8 + 2] = acadoWorkspace.conValueOut[4]; +acadoWorkspace.evHx[lRun1 * 8 + 3] = acadoWorkspace.conValueOut[5]; +acadoWorkspace.evHx[lRun1 * 8 + 4] = acadoWorkspace.conValueOut[6]; +acadoWorkspace.evHx[lRun1 * 8 + 5] = acadoWorkspace.conValueOut[7]; +acadoWorkspace.evHx[lRun1 * 8 + 6] = acadoWorkspace.conValueOut[8]; +acadoWorkspace.evHx[lRun1 * 8 + 7] = acadoWorkspace.conValueOut[9]; +acadoWorkspace.evHu[lRun1 * 4] = acadoWorkspace.conValueOut[10]; +acadoWorkspace.evHu[lRun1 * 4 + 1] = acadoWorkspace.conValueOut[11]; +acadoWorkspace.evHu[lRun1 * 4 + 2] = acadoWorkspace.conValueOut[12]; +acadoWorkspace.evHu[lRun1 * 4 + 3] = acadoWorkspace.conValueOut[13]; +} + +acadoWorkspace.A[2176] = acadoWorkspace.evHx[0]; +acadoWorkspace.A[2177] = acadoWorkspace.evHx[1]; +acadoWorkspace.A[2178] = acadoWorkspace.evHx[2]; +acadoWorkspace.A[2179] = acadoWorkspace.evHx[3]; +acadoWorkspace.A[2244] = acadoWorkspace.evHx[4]; +acadoWorkspace.A[2245] = acadoWorkspace.evHx[5]; +acadoWorkspace.A[2246] = acadoWorkspace.evHx[6]; +acadoWorkspace.A[2247] = acadoWorkspace.evHx[7]; + +acado_multHxC( &(acadoWorkspace.evHx[ 8 ]), acadoWorkspace.evGx, &(acadoWorkspace.A[ 2312 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 16 ]), &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.A[ 2448 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 24 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.A[ 2584 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 32 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.A[ 2720 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 40 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.A[ 2856 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 48 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.A[ 2992 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 56 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.A[ 3128 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 64 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.A[ 3264 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 72 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.A[ 3400 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 80 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.A[ 3536 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 88 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.A[ 3672 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 96 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.A[ 3808 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 104 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.A[ 3944 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 112 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.A[ 4080 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 120 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.A[ 4216 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 128 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.A[ 4352 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 136 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.A[ 4488 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 144 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.A[ 4624 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 152 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.A[ 4760 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 160 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.A[ 4896 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 168 ]), &(acadoWorkspace.evGx[ 320 ]), &(acadoWorkspace.A[ 5032 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 176 ]), &(acadoWorkspace.evGx[ 336 ]), &(acadoWorkspace.A[ 5168 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 184 ]), &(acadoWorkspace.evGx[ 352 ]), &(acadoWorkspace.A[ 5304 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 192 ]), &(acadoWorkspace.evGx[ 368 ]), &(acadoWorkspace.A[ 5440 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 200 ]), &(acadoWorkspace.evGx[ 384 ]), &(acadoWorkspace.A[ 5576 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 208 ]), &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.A[ 5712 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 216 ]), &(acadoWorkspace.evGx[ 416 ]), &(acadoWorkspace.A[ 5848 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 224 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.A[ 5984 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 232 ]), &(acadoWorkspace.evGx[ 448 ]), &(acadoWorkspace.A[ 6120 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 240 ]), &(acadoWorkspace.evGx[ 464 ]), &(acadoWorkspace.A[ 6256 ]) ); +acado_multHxC( &(acadoWorkspace.evHx[ 248 ]), &(acadoWorkspace.evGx[ 480 ]), &(acadoWorkspace.A[ 6392 ]) ); + +for (lRun2 = 0; lRun2 < 31; ++lRun2) +{ +for (lRun3 = 0; lRun3 < lRun2 + 1; ++lRun3) +{ +lRun4 = (((lRun2 + 1) * (lRun2)) / (2)) + (lRun3); +lRun5 = lRun2 + 1; +acado_multHxE( &(acadoWorkspace.evHx[ lRun2 * 8 + 8 ]), &(acadoWorkspace.E[ lRun4 * 8 ]), lRun5, lRun3 ); +} +} + +acadoWorkspace.A[2180] = acadoWorkspace.evHu[0]; +acadoWorkspace.A[2181] = acadoWorkspace.evHu[1]; +acadoWorkspace.A[2248] = acadoWorkspace.evHu[2]; +acadoWorkspace.A[2249] = acadoWorkspace.evHu[3]; +acadoWorkspace.A[2318] = acadoWorkspace.evHu[4]; +acadoWorkspace.A[2319] = acadoWorkspace.evHu[5]; +acadoWorkspace.A[2386] = acadoWorkspace.evHu[6]; +acadoWorkspace.A[2387] = acadoWorkspace.evHu[7]; +acadoWorkspace.A[2456] = acadoWorkspace.evHu[8]; +acadoWorkspace.A[2457] = acadoWorkspace.evHu[9]; +acadoWorkspace.A[2524] = acadoWorkspace.evHu[10]; +acadoWorkspace.A[2525] = acadoWorkspace.evHu[11]; +acadoWorkspace.A[2594] = acadoWorkspace.evHu[12]; +acadoWorkspace.A[2595] = acadoWorkspace.evHu[13]; +acadoWorkspace.A[2662] = acadoWorkspace.evHu[14]; +acadoWorkspace.A[2663] = acadoWorkspace.evHu[15]; +acadoWorkspace.A[2732] = acadoWorkspace.evHu[16]; +acadoWorkspace.A[2733] = acadoWorkspace.evHu[17]; +acadoWorkspace.A[2800] = acadoWorkspace.evHu[18]; +acadoWorkspace.A[2801] = acadoWorkspace.evHu[19]; +acadoWorkspace.A[2870] = acadoWorkspace.evHu[20]; +acadoWorkspace.A[2871] = acadoWorkspace.evHu[21]; +acadoWorkspace.A[2938] = acadoWorkspace.evHu[22]; +acadoWorkspace.A[2939] = acadoWorkspace.evHu[23]; +acadoWorkspace.A[3008] = acadoWorkspace.evHu[24]; +acadoWorkspace.A[3009] = acadoWorkspace.evHu[25]; +acadoWorkspace.A[3076] = acadoWorkspace.evHu[26]; +acadoWorkspace.A[3077] = acadoWorkspace.evHu[27]; +acadoWorkspace.A[3146] = acadoWorkspace.evHu[28]; +acadoWorkspace.A[3147] = acadoWorkspace.evHu[29]; +acadoWorkspace.A[3214] = acadoWorkspace.evHu[30]; +acadoWorkspace.A[3215] = acadoWorkspace.evHu[31]; +acadoWorkspace.A[3284] = acadoWorkspace.evHu[32]; +acadoWorkspace.A[3285] = acadoWorkspace.evHu[33]; +acadoWorkspace.A[3352] = acadoWorkspace.evHu[34]; +acadoWorkspace.A[3353] = acadoWorkspace.evHu[35]; +acadoWorkspace.A[3422] = acadoWorkspace.evHu[36]; +acadoWorkspace.A[3423] = acadoWorkspace.evHu[37]; +acadoWorkspace.A[3490] = acadoWorkspace.evHu[38]; +acadoWorkspace.A[3491] = acadoWorkspace.evHu[39]; +acadoWorkspace.A[3560] = acadoWorkspace.evHu[40]; +acadoWorkspace.A[3561] = acadoWorkspace.evHu[41]; +acadoWorkspace.A[3628] = acadoWorkspace.evHu[42]; +acadoWorkspace.A[3629] = acadoWorkspace.evHu[43]; +acadoWorkspace.A[3698] = acadoWorkspace.evHu[44]; +acadoWorkspace.A[3699] = acadoWorkspace.evHu[45]; +acadoWorkspace.A[3766] = acadoWorkspace.evHu[46]; +acadoWorkspace.A[3767] = acadoWorkspace.evHu[47]; +acadoWorkspace.A[3836] = acadoWorkspace.evHu[48]; +acadoWorkspace.A[3837] = acadoWorkspace.evHu[49]; +acadoWorkspace.A[3904] = acadoWorkspace.evHu[50]; +acadoWorkspace.A[3905] = acadoWorkspace.evHu[51]; +acadoWorkspace.A[3974] = acadoWorkspace.evHu[52]; +acadoWorkspace.A[3975] = acadoWorkspace.evHu[53]; +acadoWorkspace.A[4042] = acadoWorkspace.evHu[54]; +acadoWorkspace.A[4043] = acadoWorkspace.evHu[55]; +acadoWorkspace.A[4112] = acadoWorkspace.evHu[56]; +acadoWorkspace.A[4113] = acadoWorkspace.evHu[57]; +acadoWorkspace.A[4180] = acadoWorkspace.evHu[58]; +acadoWorkspace.A[4181] = acadoWorkspace.evHu[59]; +acadoWorkspace.A[4250] = acadoWorkspace.evHu[60]; +acadoWorkspace.A[4251] = acadoWorkspace.evHu[61]; +acadoWorkspace.A[4318] = acadoWorkspace.evHu[62]; +acadoWorkspace.A[4319] = acadoWorkspace.evHu[63]; +acadoWorkspace.A[4388] = acadoWorkspace.evHu[64]; +acadoWorkspace.A[4389] = acadoWorkspace.evHu[65]; +acadoWorkspace.A[4456] = acadoWorkspace.evHu[66]; +acadoWorkspace.A[4457] = acadoWorkspace.evHu[67]; +acadoWorkspace.A[4526] = acadoWorkspace.evHu[68]; +acadoWorkspace.A[4527] = acadoWorkspace.evHu[69]; +acadoWorkspace.A[4594] = acadoWorkspace.evHu[70]; +acadoWorkspace.A[4595] = acadoWorkspace.evHu[71]; +acadoWorkspace.A[4664] = acadoWorkspace.evHu[72]; +acadoWorkspace.A[4665] = acadoWorkspace.evHu[73]; +acadoWorkspace.A[4732] = acadoWorkspace.evHu[74]; +acadoWorkspace.A[4733] = acadoWorkspace.evHu[75]; +acadoWorkspace.A[4802] = acadoWorkspace.evHu[76]; +acadoWorkspace.A[4803] = acadoWorkspace.evHu[77]; +acadoWorkspace.A[4870] = acadoWorkspace.evHu[78]; +acadoWorkspace.A[4871] = acadoWorkspace.evHu[79]; +acadoWorkspace.A[4940] = acadoWorkspace.evHu[80]; +acadoWorkspace.A[4941] = acadoWorkspace.evHu[81]; +acadoWorkspace.A[5008] = acadoWorkspace.evHu[82]; +acadoWorkspace.A[5009] = acadoWorkspace.evHu[83]; +acadoWorkspace.A[5078] = acadoWorkspace.evHu[84]; +acadoWorkspace.A[5079] = acadoWorkspace.evHu[85]; +acadoWorkspace.A[5146] = acadoWorkspace.evHu[86]; +acadoWorkspace.A[5147] = acadoWorkspace.evHu[87]; +acadoWorkspace.A[5216] = acadoWorkspace.evHu[88]; +acadoWorkspace.A[5217] = acadoWorkspace.evHu[89]; +acadoWorkspace.A[5284] = acadoWorkspace.evHu[90]; +acadoWorkspace.A[5285] = acadoWorkspace.evHu[91]; +acadoWorkspace.A[5354] = acadoWorkspace.evHu[92]; +acadoWorkspace.A[5355] = acadoWorkspace.evHu[93]; +acadoWorkspace.A[5422] = acadoWorkspace.evHu[94]; +acadoWorkspace.A[5423] = acadoWorkspace.evHu[95]; +acadoWorkspace.A[5492] = acadoWorkspace.evHu[96]; +acadoWorkspace.A[5493] = acadoWorkspace.evHu[97]; +acadoWorkspace.A[5560] = acadoWorkspace.evHu[98]; +acadoWorkspace.A[5561] = acadoWorkspace.evHu[99]; +acadoWorkspace.A[5630] = acadoWorkspace.evHu[100]; +acadoWorkspace.A[5631] = acadoWorkspace.evHu[101]; +acadoWorkspace.A[5698] = acadoWorkspace.evHu[102]; +acadoWorkspace.A[5699] = acadoWorkspace.evHu[103]; +acadoWorkspace.A[5768] = acadoWorkspace.evHu[104]; +acadoWorkspace.A[5769] = acadoWorkspace.evHu[105]; +acadoWorkspace.A[5836] = acadoWorkspace.evHu[106]; +acadoWorkspace.A[5837] = acadoWorkspace.evHu[107]; +acadoWorkspace.A[5906] = acadoWorkspace.evHu[108]; +acadoWorkspace.A[5907] = acadoWorkspace.evHu[109]; +acadoWorkspace.A[5974] = acadoWorkspace.evHu[110]; +acadoWorkspace.A[5975] = acadoWorkspace.evHu[111]; +acadoWorkspace.A[6044] = acadoWorkspace.evHu[112]; +acadoWorkspace.A[6045] = acadoWorkspace.evHu[113]; +acadoWorkspace.A[6112] = acadoWorkspace.evHu[114]; +acadoWorkspace.A[6113] = acadoWorkspace.evHu[115]; +acadoWorkspace.A[6182] = acadoWorkspace.evHu[116]; +acadoWorkspace.A[6183] = acadoWorkspace.evHu[117]; +acadoWorkspace.A[6250] = acadoWorkspace.evHu[118]; +acadoWorkspace.A[6251] = acadoWorkspace.evHu[119]; +acadoWorkspace.A[6320] = acadoWorkspace.evHu[120]; +acadoWorkspace.A[6321] = acadoWorkspace.evHu[121]; +acadoWorkspace.A[6388] = acadoWorkspace.evHu[122]; +acadoWorkspace.A[6389] = acadoWorkspace.evHu[123]; +acadoWorkspace.A[6458] = acadoWorkspace.evHu[124]; +acadoWorkspace.A[6459] = acadoWorkspace.evHu[125]; +acadoWorkspace.A[6526] = acadoWorkspace.evHu[126]; +acadoWorkspace.A[6527] = acadoWorkspace.evHu[127]; +acadoWorkspace.lbA[32] = - acadoWorkspace.evH[0]; +acadoWorkspace.lbA[33] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[1]; +acadoWorkspace.lbA[34] = - acadoWorkspace.evH[2]; +acadoWorkspace.lbA[35] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[3]; +acadoWorkspace.lbA[36] = - acadoWorkspace.evH[4]; +acadoWorkspace.lbA[37] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[5]; +acadoWorkspace.lbA[38] = - acadoWorkspace.evH[6]; +acadoWorkspace.lbA[39] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[7]; +acadoWorkspace.lbA[40] = - acadoWorkspace.evH[8]; +acadoWorkspace.lbA[41] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[9]; +acadoWorkspace.lbA[42] = - acadoWorkspace.evH[10]; +acadoWorkspace.lbA[43] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[11]; +acadoWorkspace.lbA[44] = - acadoWorkspace.evH[12]; +acadoWorkspace.lbA[45] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[13]; +acadoWorkspace.lbA[46] = - acadoWorkspace.evH[14]; +acadoWorkspace.lbA[47] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[15]; +acadoWorkspace.lbA[48] = - acadoWorkspace.evH[16]; +acadoWorkspace.lbA[49] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[17]; +acadoWorkspace.lbA[50] = - acadoWorkspace.evH[18]; +acadoWorkspace.lbA[51] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[19]; +acadoWorkspace.lbA[52] = - acadoWorkspace.evH[20]; +acadoWorkspace.lbA[53] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[21]; +acadoWorkspace.lbA[54] = - acadoWorkspace.evH[22]; +acadoWorkspace.lbA[55] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[23]; +acadoWorkspace.lbA[56] = - acadoWorkspace.evH[24]; +acadoWorkspace.lbA[57] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[25]; +acadoWorkspace.lbA[58] = - acadoWorkspace.evH[26]; +acadoWorkspace.lbA[59] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[27]; +acadoWorkspace.lbA[60] = - acadoWorkspace.evH[28]; +acadoWorkspace.lbA[61] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[29]; +acadoWorkspace.lbA[62] = - acadoWorkspace.evH[30]; +acadoWorkspace.lbA[63] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[31]; +acadoWorkspace.lbA[64] = - acadoWorkspace.evH[32]; +acadoWorkspace.lbA[65] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[33]; +acadoWorkspace.lbA[66] = - acadoWorkspace.evH[34]; +acadoWorkspace.lbA[67] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[35]; +acadoWorkspace.lbA[68] = - acadoWorkspace.evH[36]; +acadoWorkspace.lbA[69] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[37]; +acadoWorkspace.lbA[70] = - acadoWorkspace.evH[38]; +acadoWorkspace.lbA[71] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[39]; +acadoWorkspace.lbA[72] = - acadoWorkspace.evH[40]; +acadoWorkspace.lbA[73] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[41]; +acadoWorkspace.lbA[74] = - acadoWorkspace.evH[42]; +acadoWorkspace.lbA[75] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[43]; +acadoWorkspace.lbA[76] = - acadoWorkspace.evH[44]; +acadoWorkspace.lbA[77] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[45]; +acadoWorkspace.lbA[78] = - acadoWorkspace.evH[46]; +acadoWorkspace.lbA[79] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[47]; +acadoWorkspace.lbA[80] = - acadoWorkspace.evH[48]; +acadoWorkspace.lbA[81] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[49]; +acadoWorkspace.lbA[82] = - acadoWorkspace.evH[50]; +acadoWorkspace.lbA[83] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[51]; +acadoWorkspace.lbA[84] = - acadoWorkspace.evH[52]; +acadoWorkspace.lbA[85] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[53]; +acadoWorkspace.lbA[86] = - acadoWorkspace.evH[54]; +acadoWorkspace.lbA[87] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[55]; +acadoWorkspace.lbA[88] = - acadoWorkspace.evH[56]; +acadoWorkspace.lbA[89] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[57]; +acadoWorkspace.lbA[90] = - acadoWorkspace.evH[58]; +acadoWorkspace.lbA[91] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[59]; +acadoWorkspace.lbA[92] = - acadoWorkspace.evH[60]; +acadoWorkspace.lbA[93] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[61]; +acadoWorkspace.lbA[94] = - acadoWorkspace.evH[62]; +acadoWorkspace.lbA[95] = (real_t)-1.0000000000000000e+12 - acadoWorkspace.evH[63]; + +acadoWorkspace.ubA[32] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[0]; +acadoWorkspace.ubA[33] = - acadoWorkspace.evH[1]; +acadoWorkspace.ubA[34] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[2]; +acadoWorkspace.ubA[35] = - acadoWorkspace.evH[3]; +acadoWorkspace.ubA[36] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[4]; +acadoWorkspace.ubA[37] = - acadoWorkspace.evH[5]; +acadoWorkspace.ubA[38] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[6]; +acadoWorkspace.ubA[39] = - acadoWorkspace.evH[7]; +acadoWorkspace.ubA[40] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[8]; +acadoWorkspace.ubA[41] = - acadoWorkspace.evH[9]; +acadoWorkspace.ubA[42] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[10]; +acadoWorkspace.ubA[43] = - acadoWorkspace.evH[11]; +acadoWorkspace.ubA[44] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[12]; +acadoWorkspace.ubA[45] = - acadoWorkspace.evH[13]; +acadoWorkspace.ubA[46] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[14]; +acadoWorkspace.ubA[47] = - acadoWorkspace.evH[15]; +acadoWorkspace.ubA[48] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[16]; +acadoWorkspace.ubA[49] = - acadoWorkspace.evH[17]; +acadoWorkspace.ubA[50] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[18]; +acadoWorkspace.ubA[51] = - acadoWorkspace.evH[19]; +acadoWorkspace.ubA[52] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[20]; +acadoWorkspace.ubA[53] = - acadoWorkspace.evH[21]; +acadoWorkspace.ubA[54] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[22]; +acadoWorkspace.ubA[55] = - acadoWorkspace.evH[23]; +acadoWorkspace.ubA[56] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[24]; +acadoWorkspace.ubA[57] = - acadoWorkspace.evH[25]; +acadoWorkspace.ubA[58] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[26]; +acadoWorkspace.ubA[59] = - acadoWorkspace.evH[27]; +acadoWorkspace.ubA[60] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[28]; +acadoWorkspace.ubA[61] = - acadoWorkspace.evH[29]; +acadoWorkspace.ubA[62] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[30]; +acadoWorkspace.ubA[63] = - acadoWorkspace.evH[31]; +acadoWorkspace.ubA[64] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[32]; +acadoWorkspace.ubA[65] = - acadoWorkspace.evH[33]; +acadoWorkspace.ubA[66] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[34]; +acadoWorkspace.ubA[67] = - acadoWorkspace.evH[35]; +acadoWorkspace.ubA[68] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[36]; +acadoWorkspace.ubA[69] = - acadoWorkspace.evH[37]; +acadoWorkspace.ubA[70] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[38]; +acadoWorkspace.ubA[71] = - acadoWorkspace.evH[39]; +acadoWorkspace.ubA[72] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[40]; +acadoWorkspace.ubA[73] = - acadoWorkspace.evH[41]; +acadoWorkspace.ubA[74] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[42]; +acadoWorkspace.ubA[75] = - acadoWorkspace.evH[43]; +acadoWorkspace.ubA[76] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[44]; +acadoWorkspace.ubA[77] = - acadoWorkspace.evH[45]; +acadoWorkspace.ubA[78] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[46]; +acadoWorkspace.ubA[79] = - acadoWorkspace.evH[47]; +acadoWorkspace.ubA[80] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[48]; +acadoWorkspace.ubA[81] = - acadoWorkspace.evH[49]; +acadoWorkspace.ubA[82] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[50]; +acadoWorkspace.ubA[83] = - acadoWorkspace.evH[51]; +acadoWorkspace.ubA[84] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[52]; +acadoWorkspace.ubA[85] = - acadoWorkspace.evH[53]; +acadoWorkspace.ubA[86] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[54]; +acadoWorkspace.ubA[87] = - acadoWorkspace.evH[55]; +acadoWorkspace.ubA[88] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[56]; +acadoWorkspace.ubA[89] = - acadoWorkspace.evH[57]; +acadoWorkspace.ubA[90] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[58]; +acadoWorkspace.ubA[91] = - acadoWorkspace.evH[59]; +acadoWorkspace.ubA[92] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[60]; +acadoWorkspace.ubA[93] = - acadoWorkspace.evH[61]; +acadoWorkspace.ubA[94] = (real_t)1.0000000000000000e+12 - acadoWorkspace.evH[62]; +acadoWorkspace.ubA[95] = - acadoWorkspace.evH[63]; + +acado_macHxd( &(acadoWorkspace.evHx[ 8 ]), acadoWorkspace.d, &(acadoWorkspace.lbA[ 34 ]), &(acadoWorkspace.ubA[ 34 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 16 ]), &(acadoWorkspace.d[ 4 ]), &(acadoWorkspace.lbA[ 36 ]), &(acadoWorkspace.ubA[ 36 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 24 ]), &(acadoWorkspace.d[ 8 ]), &(acadoWorkspace.lbA[ 38 ]), &(acadoWorkspace.ubA[ 38 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 32 ]), &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.lbA[ 40 ]), &(acadoWorkspace.ubA[ 40 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 40 ]), &(acadoWorkspace.d[ 16 ]), &(acadoWorkspace.lbA[ 42 ]), &(acadoWorkspace.ubA[ 42 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 48 ]), &(acadoWorkspace.d[ 20 ]), &(acadoWorkspace.lbA[ 44 ]), &(acadoWorkspace.ubA[ 44 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 56 ]), &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.lbA[ 46 ]), &(acadoWorkspace.ubA[ 46 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 64 ]), &(acadoWorkspace.d[ 28 ]), &(acadoWorkspace.lbA[ 48 ]), &(acadoWorkspace.ubA[ 48 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 72 ]), &(acadoWorkspace.d[ 32 ]), &(acadoWorkspace.lbA[ 50 ]), &(acadoWorkspace.ubA[ 50 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 80 ]), &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.lbA[ 52 ]), &(acadoWorkspace.ubA[ 52 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 88 ]), &(acadoWorkspace.d[ 40 ]), &(acadoWorkspace.lbA[ 54 ]), &(acadoWorkspace.ubA[ 54 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 96 ]), &(acadoWorkspace.d[ 44 ]), &(acadoWorkspace.lbA[ 56 ]), &(acadoWorkspace.ubA[ 56 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 104 ]), &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.lbA[ 58 ]), &(acadoWorkspace.ubA[ 58 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 112 ]), &(acadoWorkspace.d[ 52 ]), &(acadoWorkspace.lbA[ 60 ]), &(acadoWorkspace.ubA[ 60 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 120 ]), &(acadoWorkspace.d[ 56 ]), &(acadoWorkspace.lbA[ 62 ]), &(acadoWorkspace.ubA[ 62 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 128 ]), &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.lbA[ 64 ]), &(acadoWorkspace.ubA[ 64 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 136 ]), &(acadoWorkspace.d[ 64 ]), &(acadoWorkspace.lbA[ 66 ]), &(acadoWorkspace.ubA[ 66 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 144 ]), &(acadoWorkspace.d[ 68 ]), &(acadoWorkspace.lbA[ 68 ]), &(acadoWorkspace.ubA[ 68 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 152 ]), &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.lbA[ 70 ]), &(acadoWorkspace.ubA[ 70 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 160 ]), &(acadoWorkspace.d[ 76 ]), &(acadoWorkspace.lbA[ 72 ]), &(acadoWorkspace.ubA[ 72 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 168 ]), &(acadoWorkspace.d[ 80 ]), &(acadoWorkspace.lbA[ 74 ]), &(acadoWorkspace.ubA[ 74 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 176 ]), &(acadoWorkspace.d[ 84 ]), &(acadoWorkspace.lbA[ 76 ]), &(acadoWorkspace.ubA[ 76 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 184 ]), &(acadoWorkspace.d[ 88 ]), &(acadoWorkspace.lbA[ 78 ]), &(acadoWorkspace.ubA[ 78 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 192 ]), &(acadoWorkspace.d[ 92 ]), &(acadoWorkspace.lbA[ 80 ]), &(acadoWorkspace.ubA[ 80 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 200 ]), &(acadoWorkspace.d[ 96 ]), &(acadoWorkspace.lbA[ 82 ]), &(acadoWorkspace.ubA[ 82 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 208 ]), &(acadoWorkspace.d[ 100 ]), &(acadoWorkspace.lbA[ 84 ]), &(acadoWorkspace.ubA[ 84 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 216 ]), &(acadoWorkspace.d[ 104 ]), &(acadoWorkspace.lbA[ 86 ]), &(acadoWorkspace.ubA[ 86 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 224 ]), &(acadoWorkspace.d[ 108 ]), &(acadoWorkspace.lbA[ 88 ]), &(acadoWorkspace.ubA[ 88 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 232 ]), &(acadoWorkspace.d[ 112 ]), &(acadoWorkspace.lbA[ 90 ]), &(acadoWorkspace.ubA[ 90 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 240 ]), &(acadoWorkspace.d[ 116 ]), &(acadoWorkspace.lbA[ 92 ]), &(acadoWorkspace.ubA[ 92 ]) ); +acado_macHxd( &(acadoWorkspace.evHx[ 248 ]), &(acadoWorkspace.d[ 120 ]), &(acadoWorkspace.lbA[ 94 ]), &(acadoWorkspace.ubA[ 94 ]) ); + +} + +void acado_condenseFdb( ) +{ +int lRun1; +int lRun2; +int lRun3; +real_t tmp; + +acadoWorkspace.Dx0[0] = acadoVariables.x0[0] - acadoVariables.x[0]; +acadoWorkspace.Dx0[1] = acadoVariables.x0[1] - acadoVariables.x[1]; +acadoWorkspace.Dx0[2] = acadoVariables.x0[2] - acadoVariables.x[2]; +acadoWorkspace.Dx0[3] = acadoVariables.x0[3] - acadoVariables.x[3]; + +for (lRun2 = 0; lRun2 < 160; ++lRun2) +acadoWorkspace.Dy[lRun2] -= acadoVariables.y[lRun2]; + +acadoWorkspace.DyN[0] -= acadoVariables.yN[0]; +acadoWorkspace.DyN[1] -= acadoVariables.yN[1]; +acadoWorkspace.DyN[2] -= acadoVariables.yN[2]; + +acado_multRDy( acadoWorkspace.R2, acadoWorkspace.Dy, &(acadoWorkspace.g[ 4 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 10 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 20 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 30 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 40 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 50 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 60 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 70 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 80 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 90 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 100 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.g[ 24 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 110 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.g[ 26 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 120 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.g[ 28 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 130 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.g[ 30 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 140 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.g[ 32 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 150 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.g[ 34 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 160 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.g[ 36 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 170 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.g[ 38 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 180 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.g[ 40 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 190 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.g[ 42 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 200 ]), &(acadoWorkspace.Dy[ 100 ]), &(acadoWorkspace.g[ 44 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 210 ]), &(acadoWorkspace.Dy[ 105 ]), &(acadoWorkspace.g[ 46 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 220 ]), &(acadoWorkspace.Dy[ 110 ]), &(acadoWorkspace.g[ 48 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 230 ]), &(acadoWorkspace.Dy[ 115 ]), &(acadoWorkspace.g[ 50 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 240 ]), &(acadoWorkspace.Dy[ 120 ]), &(acadoWorkspace.g[ 52 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 250 ]), &(acadoWorkspace.Dy[ 125 ]), &(acadoWorkspace.g[ 54 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 260 ]), &(acadoWorkspace.Dy[ 130 ]), &(acadoWorkspace.g[ 56 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 270 ]), &(acadoWorkspace.Dy[ 135 ]), &(acadoWorkspace.g[ 58 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 280 ]), &(acadoWorkspace.Dy[ 140 ]), &(acadoWorkspace.g[ 60 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 290 ]), &(acadoWorkspace.Dy[ 145 ]), &(acadoWorkspace.g[ 62 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 300 ]), &(acadoWorkspace.Dy[ 150 ]), &(acadoWorkspace.g[ 64 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 310 ]), &(acadoWorkspace.Dy[ 155 ]), &(acadoWorkspace.g[ 66 ]) ); + +acado_multQDy( acadoWorkspace.Q2, acadoWorkspace.Dy, acadoWorkspace.QDy ); +acado_multQDy( &(acadoWorkspace.Q2[ 20 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.QDy[ 4 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 40 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.QDy[ 8 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 60 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.QDy[ 12 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 80 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.QDy[ 16 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 100 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.QDy[ 20 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 120 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.QDy[ 24 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 140 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.QDy[ 28 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 160 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.QDy[ 32 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 180 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.QDy[ 36 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 200 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.QDy[ 40 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 220 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.QDy[ 44 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 240 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.QDy[ 48 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 260 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.QDy[ 52 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 280 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.QDy[ 56 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 300 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.QDy[ 60 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 320 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.QDy[ 64 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 340 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.QDy[ 68 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 360 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.QDy[ 72 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 380 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.QDy[ 76 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 400 ]), &(acadoWorkspace.Dy[ 100 ]), &(acadoWorkspace.QDy[ 80 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 420 ]), &(acadoWorkspace.Dy[ 105 ]), &(acadoWorkspace.QDy[ 84 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 440 ]), &(acadoWorkspace.Dy[ 110 ]), &(acadoWorkspace.QDy[ 88 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 460 ]), &(acadoWorkspace.Dy[ 115 ]), &(acadoWorkspace.QDy[ 92 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 480 ]), &(acadoWorkspace.Dy[ 120 ]), &(acadoWorkspace.QDy[ 96 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 500 ]), &(acadoWorkspace.Dy[ 125 ]), &(acadoWorkspace.QDy[ 100 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 520 ]), &(acadoWorkspace.Dy[ 130 ]), &(acadoWorkspace.QDy[ 104 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 540 ]), &(acadoWorkspace.Dy[ 135 ]), &(acadoWorkspace.QDy[ 108 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 560 ]), &(acadoWorkspace.Dy[ 140 ]), &(acadoWorkspace.QDy[ 112 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 580 ]), &(acadoWorkspace.Dy[ 145 ]), &(acadoWorkspace.QDy[ 116 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 600 ]), &(acadoWorkspace.Dy[ 150 ]), &(acadoWorkspace.QDy[ 120 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 620 ]), &(acadoWorkspace.Dy[ 155 ]), &(acadoWorkspace.QDy[ 124 ]) ); + +acadoWorkspace.QDy[128] = + acadoWorkspace.QN2[0]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[1]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[2]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[129] = + acadoWorkspace.QN2[3]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[4]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[5]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[130] = + acadoWorkspace.QN2[6]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[7]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[8]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[131] = + acadoWorkspace.QN2[9]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[10]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[11]*acadoWorkspace.DyN[2]; + +for (lRun2 = 0; lRun2 < 128; ++lRun2) +acadoWorkspace.QDy[lRun2 + 4] += acadoWorkspace.Qd[lRun2]; + + +acadoWorkspace.g[0] = + acadoWorkspace.evGx[0]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[4]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[8]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[12]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[16]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[20]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[24]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[28]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[32]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[36]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[40]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[44]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[48]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[52]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[56]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[60]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[64]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[68]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[72]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[76]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[80]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[84]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[88]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[92]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[96]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[100]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[104]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[108]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[112]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[116]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[120]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[124]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[128]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[132]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[136]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[140]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[144]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[148]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[152]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[156]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[160]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[164]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[168]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[172]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[176]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[180]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[184]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[188]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[192]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[196]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[200]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[204]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[208]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[212]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[216]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[220]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[224]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[228]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[232]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[236]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[240]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[244]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[248]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[252]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[256]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[260]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[264]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[268]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[272]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[276]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[280]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[284]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[288]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[292]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[296]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[300]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[304]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[308]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[312]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[316]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[320]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[324]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[328]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[332]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[336]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[340]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[344]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[348]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[352]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[356]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[360]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[364]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[368]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[372]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[376]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[380]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[384]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[388]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[392]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[396]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[400]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[404]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[408]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[412]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[416]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[420]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[424]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[428]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[432]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[436]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[440]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[444]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[448]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[452]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[456]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[460]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[464]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[468]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[472]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[476]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[480]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[484]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[488]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[492]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[496]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[500]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[504]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[508]*acadoWorkspace.QDy[131]; +acadoWorkspace.g[1] = + acadoWorkspace.evGx[1]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[5]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[9]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[13]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[17]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[21]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[25]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[29]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[33]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[37]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[41]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[45]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[49]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[53]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[57]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[61]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[65]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[69]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[73]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[77]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[81]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[85]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[89]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[93]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[97]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[101]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[105]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[109]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[113]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[117]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[121]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[125]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[129]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[133]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[137]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[141]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[145]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[149]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[153]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[157]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[161]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[165]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[169]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[173]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[177]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[181]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[185]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[189]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[193]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[197]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[201]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[205]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[209]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[213]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[217]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[221]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[225]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[229]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[233]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[237]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[241]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[245]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[249]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[253]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[257]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[261]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[265]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[269]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[273]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[277]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[281]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[285]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[289]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[293]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[297]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[301]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[305]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[309]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[313]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[317]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[321]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[325]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[329]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[333]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[337]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[341]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[345]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[349]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[353]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[357]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[361]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[365]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[369]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[373]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[377]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[381]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[385]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[389]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[393]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[397]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[401]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[405]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[409]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[413]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[417]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[421]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[425]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[429]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[433]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[437]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[441]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[445]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[449]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[453]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[457]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[461]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[465]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[469]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[473]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[477]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[481]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[485]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[489]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[493]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[497]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[501]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[505]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[509]*acadoWorkspace.QDy[131]; +acadoWorkspace.g[2] = + acadoWorkspace.evGx[2]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[6]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[10]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[14]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[18]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[22]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[26]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[30]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[34]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[38]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[42]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[46]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[50]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[54]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[58]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[62]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[66]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[70]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[74]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[78]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[82]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[86]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[90]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[94]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[98]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[102]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[106]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[110]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[114]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[118]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[122]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[126]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[130]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[134]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[138]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[142]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[146]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[150]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[154]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[158]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[162]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[166]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[170]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[174]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[178]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[182]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[186]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[190]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[194]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[198]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[202]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[206]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[210]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[214]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[218]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[222]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[226]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[230]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[234]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[238]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[242]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[246]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[250]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[254]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[258]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[262]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[266]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[270]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[274]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[278]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[282]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[286]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[290]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[294]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[298]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[302]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[306]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[310]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[314]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[318]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[322]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[326]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[330]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[334]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[338]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[342]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[346]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[350]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[354]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[358]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[362]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[366]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[370]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[374]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[378]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[382]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[386]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[390]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[394]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[398]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[402]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[406]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[410]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[414]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[418]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[422]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[426]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[430]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[434]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[438]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[442]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[446]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[450]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[454]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[458]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[462]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[466]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[470]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[474]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[478]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[482]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[486]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[490]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[494]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[498]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[502]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[506]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[510]*acadoWorkspace.QDy[131]; +acadoWorkspace.g[3] = + acadoWorkspace.evGx[3]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[7]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[11]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[15]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[19]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[23]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[27]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[31]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[35]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[39]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[43]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[47]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[51]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[55]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[59]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[63]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[67]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[71]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[75]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[79]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[83]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[87]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[91]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[95]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[99]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[103]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[107]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[111]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[115]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[119]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[123]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[127]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[131]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[135]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[139]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[143]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[147]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[151]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[155]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[159]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[163]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[167]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[171]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[175]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[179]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[183]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[187]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[191]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[195]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[199]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[203]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[207]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[211]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[215]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[219]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[223]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[227]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[231]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[235]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[239]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[243]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[247]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[251]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[255]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[259]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[263]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[267]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[271]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[275]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[279]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[283]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[287]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[291]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[295]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[299]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[303]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[307]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[311]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[315]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[319]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[323]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[327]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[331]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[335]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[339]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[343]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[347]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[351]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[355]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[359]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[363]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[367]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[371]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[375]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[379]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[383]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[387]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[391]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[395]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[399]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[403]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[407]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[411]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[415]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[419]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[423]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[427]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[431]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[435]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[439]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[443]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[447]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[451]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[455]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[459]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[463]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[467]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[471]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[475]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[479]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[483]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[487]*acadoWorkspace.QDy[125] + acadoWorkspace.evGx[491]*acadoWorkspace.QDy[126] + acadoWorkspace.evGx[495]*acadoWorkspace.QDy[127] + acadoWorkspace.evGx[499]*acadoWorkspace.QDy[128] + acadoWorkspace.evGx[503]*acadoWorkspace.QDy[129] + acadoWorkspace.evGx[507]*acadoWorkspace.QDy[130] + acadoWorkspace.evGx[511]*acadoWorkspace.QDy[131]; + + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +for (lRun2 = lRun1; lRun2 < 32; ++lRun2) +{ +lRun3 = (((lRun2 + 1) * (lRun2)) / (2)) + (lRun1); +acado_multEQDy( &(acadoWorkspace.E[ lRun3 * 8 ]), &(acadoWorkspace.QDy[ lRun2 * 4 + 4 ]), &(acadoWorkspace.g[ lRun1 * 2 + 4 ]) ); +} +} + +acadoWorkspace.lb[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.lb[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.lb[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.lb[3] = acadoWorkspace.Dx0[3]; +acadoWorkspace.ub[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.ub[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.ub[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.ub[3] = acadoWorkspace.Dx0[3]; +tmp = acadoVariables.x[5] + acadoWorkspace.d[1]; +acadoWorkspace.lbA[0] = - tmp; +acadoWorkspace.ubA[0] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[9] + acadoWorkspace.d[5]; +acadoWorkspace.lbA[1] = - tmp; +acadoWorkspace.ubA[1] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[13] + acadoWorkspace.d[9]; +acadoWorkspace.lbA[2] = - tmp; +acadoWorkspace.ubA[2] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[17] + acadoWorkspace.d[13]; +acadoWorkspace.lbA[3] = - tmp; +acadoWorkspace.ubA[3] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[21] + acadoWorkspace.d[17]; +acadoWorkspace.lbA[4] = - tmp; +acadoWorkspace.ubA[4] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[25] + acadoWorkspace.d[21]; +acadoWorkspace.lbA[5] = - tmp; +acadoWorkspace.ubA[5] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[29] + acadoWorkspace.d[25]; +acadoWorkspace.lbA[6] = - tmp; +acadoWorkspace.ubA[6] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[33] + acadoWorkspace.d[29]; +acadoWorkspace.lbA[7] = - tmp; +acadoWorkspace.ubA[7] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[37] + acadoWorkspace.d[33]; +acadoWorkspace.lbA[8] = - tmp; +acadoWorkspace.ubA[8] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[41] + acadoWorkspace.d[37]; +acadoWorkspace.lbA[9] = - tmp; +acadoWorkspace.ubA[9] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[45] + acadoWorkspace.d[41]; +acadoWorkspace.lbA[10] = - tmp; +acadoWorkspace.ubA[10] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[49] + acadoWorkspace.d[45]; +acadoWorkspace.lbA[11] = - tmp; +acadoWorkspace.ubA[11] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[53] + acadoWorkspace.d[49]; +acadoWorkspace.lbA[12] = - tmp; +acadoWorkspace.ubA[12] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[57] + acadoWorkspace.d[53]; +acadoWorkspace.lbA[13] = - tmp; +acadoWorkspace.ubA[13] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[61] + acadoWorkspace.d[57]; +acadoWorkspace.lbA[14] = - tmp; +acadoWorkspace.ubA[14] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[65] + acadoWorkspace.d[61]; +acadoWorkspace.lbA[15] = - tmp; +acadoWorkspace.ubA[15] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[69] + acadoWorkspace.d[65]; +acadoWorkspace.lbA[16] = - tmp; +acadoWorkspace.ubA[16] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[73] + acadoWorkspace.d[69]; +acadoWorkspace.lbA[17] = - tmp; +acadoWorkspace.ubA[17] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[77] + acadoWorkspace.d[73]; +acadoWorkspace.lbA[18] = - tmp; +acadoWorkspace.ubA[18] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[81] + acadoWorkspace.d[77]; +acadoWorkspace.lbA[19] = - tmp; +acadoWorkspace.ubA[19] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[85] + acadoWorkspace.d[81]; +acadoWorkspace.lbA[20] = - tmp; +acadoWorkspace.ubA[20] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[89] + acadoWorkspace.d[85]; +acadoWorkspace.lbA[21] = - tmp; +acadoWorkspace.ubA[21] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[93] + acadoWorkspace.d[89]; +acadoWorkspace.lbA[22] = - tmp; +acadoWorkspace.ubA[22] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[97] + acadoWorkspace.d[93]; +acadoWorkspace.lbA[23] = - tmp; +acadoWorkspace.ubA[23] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[101] + acadoWorkspace.d[97]; +acadoWorkspace.lbA[24] = - tmp; +acadoWorkspace.ubA[24] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[105] + acadoWorkspace.d[101]; +acadoWorkspace.lbA[25] = - tmp; +acadoWorkspace.ubA[25] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[109] + acadoWorkspace.d[105]; +acadoWorkspace.lbA[26] = - tmp; +acadoWorkspace.ubA[26] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[113] + acadoWorkspace.d[109]; +acadoWorkspace.lbA[27] = - tmp; +acadoWorkspace.ubA[27] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[117] + acadoWorkspace.d[113]; +acadoWorkspace.lbA[28] = - tmp; +acadoWorkspace.ubA[28] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[121] + acadoWorkspace.d[117]; +acadoWorkspace.lbA[29] = - tmp; +acadoWorkspace.ubA[29] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[125] + acadoWorkspace.d[121]; +acadoWorkspace.lbA[30] = - tmp; +acadoWorkspace.ubA[30] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[129] + acadoWorkspace.d[125]; +acadoWorkspace.lbA[31] = - tmp; +acadoWorkspace.ubA[31] = (real_t)1.0000000000000000e+12 - tmp; + +} + +void acado_expand( ) +{ +int lRun1; +int lRun2; +int lRun3; +acadoVariables.x[0] += acadoWorkspace.x[0]; +acadoVariables.x[1] += acadoWorkspace.x[1]; +acadoVariables.x[2] += acadoWorkspace.x[2]; +acadoVariables.x[3] += acadoWorkspace.x[3]; + +acadoVariables.u[0] += acadoWorkspace.x[4]; +acadoVariables.u[1] += acadoWorkspace.x[5]; +acadoVariables.u[2] += acadoWorkspace.x[6]; +acadoVariables.u[3] += acadoWorkspace.x[7]; +acadoVariables.u[4] += acadoWorkspace.x[8]; +acadoVariables.u[5] += acadoWorkspace.x[9]; +acadoVariables.u[6] += acadoWorkspace.x[10]; +acadoVariables.u[7] += acadoWorkspace.x[11]; +acadoVariables.u[8] += acadoWorkspace.x[12]; +acadoVariables.u[9] += acadoWorkspace.x[13]; +acadoVariables.u[10] += acadoWorkspace.x[14]; +acadoVariables.u[11] += acadoWorkspace.x[15]; +acadoVariables.u[12] += acadoWorkspace.x[16]; +acadoVariables.u[13] += acadoWorkspace.x[17]; +acadoVariables.u[14] += acadoWorkspace.x[18]; +acadoVariables.u[15] += acadoWorkspace.x[19]; +acadoVariables.u[16] += acadoWorkspace.x[20]; +acadoVariables.u[17] += acadoWorkspace.x[21]; +acadoVariables.u[18] += acadoWorkspace.x[22]; +acadoVariables.u[19] += acadoWorkspace.x[23]; +acadoVariables.u[20] += acadoWorkspace.x[24]; +acadoVariables.u[21] += acadoWorkspace.x[25]; +acadoVariables.u[22] += acadoWorkspace.x[26]; +acadoVariables.u[23] += acadoWorkspace.x[27]; +acadoVariables.u[24] += acadoWorkspace.x[28]; +acadoVariables.u[25] += acadoWorkspace.x[29]; +acadoVariables.u[26] += acadoWorkspace.x[30]; +acadoVariables.u[27] += acadoWorkspace.x[31]; +acadoVariables.u[28] += acadoWorkspace.x[32]; +acadoVariables.u[29] += acadoWorkspace.x[33]; +acadoVariables.u[30] += acadoWorkspace.x[34]; +acadoVariables.u[31] += acadoWorkspace.x[35]; +acadoVariables.u[32] += acadoWorkspace.x[36]; +acadoVariables.u[33] += acadoWorkspace.x[37]; +acadoVariables.u[34] += acadoWorkspace.x[38]; +acadoVariables.u[35] += acadoWorkspace.x[39]; +acadoVariables.u[36] += acadoWorkspace.x[40]; +acadoVariables.u[37] += acadoWorkspace.x[41]; +acadoVariables.u[38] += acadoWorkspace.x[42]; +acadoVariables.u[39] += acadoWorkspace.x[43]; +acadoVariables.u[40] += acadoWorkspace.x[44]; +acadoVariables.u[41] += acadoWorkspace.x[45]; +acadoVariables.u[42] += acadoWorkspace.x[46]; +acadoVariables.u[43] += acadoWorkspace.x[47]; +acadoVariables.u[44] += acadoWorkspace.x[48]; +acadoVariables.u[45] += acadoWorkspace.x[49]; +acadoVariables.u[46] += acadoWorkspace.x[50]; +acadoVariables.u[47] += acadoWorkspace.x[51]; +acadoVariables.u[48] += acadoWorkspace.x[52]; +acadoVariables.u[49] += acadoWorkspace.x[53]; +acadoVariables.u[50] += acadoWorkspace.x[54]; +acadoVariables.u[51] += acadoWorkspace.x[55]; +acadoVariables.u[52] += acadoWorkspace.x[56]; +acadoVariables.u[53] += acadoWorkspace.x[57]; +acadoVariables.u[54] += acadoWorkspace.x[58]; +acadoVariables.u[55] += acadoWorkspace.x[59]; +acadoVariables.u[56] += acadoWorkspace.x[60]; +acadoVariables.u[57] += acadoWorkspace.x[61]; +acadoVariables.u[58] += acadoWorkspace.x[62]; +acadoVariables.u[59] += acadoWorkspace.x[63]; +acadoVariables.u[60] += acadoWorkspace.x[64]; +acadoVariables.u[61] += acadoWorkspace.x[65]; +acadoVariables.u[62] += acadoWorkspace.x[66]; +acadoVariables.u[63] += acadoWorkspace.x[67]; + +acadoVariables.x[4] += + acadoWorkspace.evGx[0]*acadoWorkspace.x[0] + acadoWorkspace.evGx[1]*acadoWorkspace.x[1] + acadoWorkspace.evGx[2]*acadoWorkspace.x[2] + acadoWorkspace.evGx[3]*acadoWorkspace.x[3] + acadoWorkspace.d[0]; +acadoVariables.x[5] += + acadoWorkspace.evGx[4]*acadoWorkspace.x[0] + acadoWorkspace.evGx[5]*acadoWorkspace.x[1] + acadoWorkspace.evGx[6]*acadoWorkspace.x[2] + acadoWorkspace.evGx[7]*acadoWorkspace.x[3] + acadoWorkspace.d[1]; +acadoVariables.x[6] += + acadoWorkspace.evGx[8]*acadoWorkspace.x[0] + acadoWorkspace.evGx[9]*acadoWorkspace.x[1] + acadoWorkspace.evGx[10]*acadoWorkspace.x[2] + acadoWorkspace.evGx[11]*acadoWorkspace.x[3] + acadoWorkspace.d[2]; +acadoVariables.x[7] += + acadoWorkspace.evGx[12]*acadoWorkspace.x[0] + acadoWorkspace.evGx[13]*acadoWorkspace.x[1] + acadoWorkspace.evGx[14]*acadoWorkspace.x[2] + acadoWorkspace.evGx[15]*acadoWorkspace.x[3] + acadoWorkspace.d[3]; +acadoVariables.x[8] += + acadoWorkspace.evGx[16]*acadoWorkspace.x[0] + acadoWorkspace.evGx[17]*acadoWorkspace.x[1] + acadoWorkspace.evGx[18]*acadoWorkspace.x[2] + acadoWorkspace.evGx[19]*acadoWorkspace.x[3] + acadoWorkspace.d[4]; +acadoVariables.x[9] += + acadoWorkspace.evGx[20]*acadoWorkspace.x[0] + acadoWorkspace.evGx[21]*acadoWorkspace.x[1] + acadoWorkspace.evGx[22]*acadoWorkspace.x[2] + acadoWorkspace.evGx[23]*acadoWorkspace.x[3] + acadoWorkspace.d[5]; +acadoVariables.x[10] += + acadoWorkspace.evGx[24]*acadoWorkspace.x[0] + acadoWorkspace.evGx[25]*acadoWorkspace.x[1] + acadoWorkspace.evGx[26]*acadoWorkspace.x[2] + acadoWorkspace.evGx[27]*acadoWorkspace.x[3] + acadoWorkspace.d[6]; +acadoVariables.x[11] += + acadoWorkspace.evGx[28]*acadoWorkspace.x[0] + acadoWorkspace.evGx[29]*acadoWorkspace.x[1] + acadoWorkspace.evGx[30]*acadoWorkspace.x[2] + acadoWorkspace.evGx[31]*acadoWorkspace.x[3] + acadoWorkspace.d[7]; +acadoVariables.x[12] += + acadoWorkspace.evGx[32]*acadoWorkspace.x[0] + acadoWorkspace.evGx[33]*acadoWorkspace.x[1] + acadoWorkspace.evGx[34]*acadoWorkspace.x[2] + acadoWorkspace.evGx[35]*acadoWorkspace.x[3] + acadoWorkspace.d[8]; +acadoVariables.x[13] += + acadoWorkspace.evGx[36]*acadoWorkspace.x[0] + acadoWorkspace.evGx[37]*acadoWorkspace.x[1] + acadoWorkspace.evGx[38]*acadoWorkspace.x[2] + acadoWorkspace.evGx[39]*acadoWorkspace.x[3] + acadoWorkspace.d[9]; +acadoVariables.x[14] += + acadoWorkspace.evGx[40]*acadoWorkspace.x[0] + acadoWorkspace.evGx[41]*acadoWorkspace.x[1] + acadoWorkspace.evGx[42]*acadoWorkspace.x[2] + acadoWorkspace.evGx[43]*acadoWorkspace.x[3] + acadoWorkspace.d[10]; +acadoVariables.x[15] += + acadoWorkspace.evGx[44]*acadoWorkspace.x[0] + acadoWorkspace.evGx[45]*acadoWorkspace.x[1] + acadoWorkspace.evGx[46]*acadoWorkspace.x[2] + acadoWorkspace.evGx[47]*acadoWorkspace.x[3] + acadoWorkspace.d[11]; +acadoVariables.x[16] += + acadoWorkspace.evGx[48]*acadoWorkspace.x[0] + acadoWorkspace.evGx[49]*acadoWorkspace.x[1] + acadoWorkspace.evGx[50]*acadoWorkspace.x[2] + acadoWorkspace.evGx[51]*acadoWorkspace.x[3] + acadoWorkspace.d[12]; +acadoVariables.x[17] += + acadoWorkspace.evGx[52]*acadoWorkspace.x[0] + acadoWorkspace.evGx[53]*acadoWorkspace.x[1] + acadoWorkspace.evGx[54]*acadoWorkspace.x[2] + acadoWorkspace.evGx[55]*acadoWorkspace.x[3] + acadoWorkspace.d[13]; +acadoVariables.x[18] += + acadoWorkspace.evGx[56]*acadoWorkspace.x[0] + acadoWorkspace.evGx[57]*acadoWorkspace.x[1] + acadoWorkspace.evGx[58]*acadoWorkspace.x[2] + acadoWorkspace.evGx[59]*acadoWorkspace.x[3] + acadoWorkspace.d[14]; +acadoVariables.x[19] += + acadoWorkspace.evGx[60]*acadoWorkspace.x[0] + acadoWorkspace.evGx[61]*acadoWorkspace.x[1] + acadoWorkspace.evGx[62]*acadoWorkspace.x[2] + acadoWorkspace.evGx[63]*acadoWorkspace.x[3] + acadoWorkspace.d[15]; +acadoVariables.x[20] += + acadoWorkspace.evGx[64]*acadoWorkspace.x[0] + acadoWorkspace.evGx[65]*acadoWorkspace.x[1] + acadoWorkspace.evGx[66]*acadoWorkspace.x[2] + acadoWorkspace.evGx[67]*acadoWorkspace.x[3] + acadoWorkspace.d[16]; +acadoVariables.x[21] += + acadoWorkspace.evGx[68]*acadoWorkspace.x[0] + acadoWorkspace.evGx[69]*acadoWorkspace.x[1] + acadoWorkspace.evGx[70]*acadoWorkspace.x[2] + acadoWorkspace.evGx[71]*acadoWorkspace.x[3] + acadoWorkspace.d[17]; +acadoVariables.x[22] += + acadoWorkspace.evGx[72]*acadoWorkspace.x[0] + acadoWorkspace.evGx[73]*acadoWorkspace.x[1] + acadoWorkspace.evGx[74]*acadoWorkspace.x[2] + acadoWorkspace.evGx[75]*acadoWorkspace.x[3] + acadoWorkspace.d[18]; +acadoVariables.x[23] += + acadoWorkspace.evGx[76]*acadoWorkspace.x[0] + acadoWorkspace.evGx[77]*acadoWorkspace.x[1] + acadoWorkspace.evGx[78]*acadoWorkspace.x[2] + acadoWorkspace.evGx[79]*acadoWorkspace.x[3] + acadoWorkspace.d[19]; +acadoVariables.x[24] += + acadoWorkspace.evGx[80]*acadoWorkspace.x[0] + acadoWorkspace.evGx[81]*acadoWorkspace.x[1] + acadoWorkspace.evGx[82]*acadoWorkspace.x[2] + acadoWorkspace.evGx[83]*acadoWorkspace.x[3] + acadoWorkspace.d[20]; +acadoVariables.x[25] += + acadoWorkspace.evGx[84]*acadoWorkspace.x[0] + acadoWorkspace.evGx[85]*acadoWorkspace.x[1] + acadoWorkspace.evGx[86]*acadoWorkspace.x[2] + acadoWorkspace.evGx[87]*acadoWorkspace.x[3] + acadoWorkspace.d[21]; +acadoVariables.x[26] += + acadoWorkspace.evGx[88]*acadoWorkspace.x[0] + acadoWorkspace.evGx[89]*acadoWorkspace.x[1] + acadoWorkspace.evGx[90]*acadoWorkspace.x[2] + acadoWorkspace.evGx[91]*acadoWorkspace.x[3] + acadoWorkspace.d[22]; +acadoVariables.x[27] += + acadoWorkspace.evGx[92]*acadoWorkspace.x[0] + acadoWorkspace.evGx[93]*acadoWorkspace.x[1] + acadoWorkspace.evGx[94]*acadoWorkspace.x[2] + acadoWorkspace.evGx[95]*acadoWorkspace.x[3] + acadoWorkspace.d[23]; +acadoVariables.x[28] += + acadoWorkspace.evGx[96]*acadoWorkspace.x[0] + acadoWorkspace.evGx[97]*acadoWorkspace.x[1] + acadoWorkspace.evGx[98]*acadoWorkspace.x[2] + acadoWorkspace.evGx[99]*acadoWorkspace.x[3] + acadoWorkspace.d[24]; +acadoVariables.x[29] += + acadoWorkspace.evGx[100]*acadoWorkspace.x[0] + acadoWorkspace.evGx[101]*acadoWorkspace.x[1] + acadoWorkspace.evGx[102]*acadoWorkspace.x[2] + acadoWorkspace.evGx[103]*acadoWorkspace.x[3] + acadoWorkspace.d[25]; +acadoVariables.x[30] += + acadoWorkspace.evGx[104]*acadoWorkspace.x[0] + acadoWorkspace.evGx[105]*acadoWorkspace.x[1] + acadoWorkspace.evGx[106]*acadoWorkspace.x[2] + acadoWorkspace.evGx[107]*acadoWorkspace.x[3] + acadoWorkspace.d[26]; +acadoVariables.x[31] += + acadoWorkspace.evGx[108]*acadoWorkspace.x[0] + acadoWorkspace.evGx[109]*acadoWorkspace.x[1] + acadoWorkspace.evGx[110]*acadoWorkspace.x[2] + acadoWorkspace.evGx[111]*acadoWorkspace.x[3] + acadoWorkspace.d[27]; +acadoVariables.x[32] += + acadoWorkspace.evGx[112]*acadoWorkspace.x[0] + acadoWorkspace.evGx[113]*acadoWorkspace.x[1] + acadoWorkspace.evGx[114]*acadoWorkspace.x[2] + acadoWorkspace.evGx[115]*acadoWorkspace.x[3] + acadoWorkspace.d[28]; +acadoVariables.x[33] += + acadoWorkspace.evGx[116]*acadoWorkspace.x[0] + acadoWorkspace.evGx[117]*acadoWorkspace.x[1] + acadoWorkspace.evGx[118]*acadoWorkspace.x[2] + acadoWorkspace.evGx[119]*acadoWorkspace.x[3] + acadoWorkspace.d[29]; +acadoVariables.x[34] += + acadoWorkspace.evGx[120]*acadoWorkspace.x[0] + acadoWorkspace.evGx[121]*acadoWorkspace.x[1] + acadoWorkspace.evGx[122]*acadoWorkspace.x[2] + acadoWorkspace.evGx[123]*acadoWorkspace.x[3] + acadoWorkspace.d[30]; +acadoVariables.x[35] += + acadoWorkspace.evGx[124]*acadoWorkspace.x[0] + acadoWorkspace.evGx[125]*acadoWorkspace.x[1] + acadoWorkspace.evGx[126]*acadoWorkspace.x[2] + acadoWorkspace.evGx[127]*acadoWorkspace.x[3] + acadoWorkspace.d[31]; +acadoVariables.x[36] += + acadoWorkspace.evGx[128]*acadoWorkspace.x[0] + acadoWorkspace.evGx[129]*acadoWorkspace.x[1] + acadoWorkspace.evGx[130]*acadoWorkspace.x[2] + acadoWorkspace.evGx[131]*acadoWorkspace.x[3] + acadoWorkspace.d[32]; +acadoVariables.x[37] += + acadoWorkspace.evGx[132]*acadoWorkspace.x[0] + acadoWorkspace.evGx[133]*acadoWorkspace.x[1] + acadoWorkspace.evGx[134]*acadoWorkspace.x[2] + acadoWorkspace.evGx[135]*acadoWorkspace.x[3] + acadoWorkspace.d[33]; +acadoVariables.x[38] += + acadoWorkspace.evGx[136]*acadoWorkspace.x[0] + acadoWorkspace.evGx[137]*acadoWorkspace.x[1] + acadoWorkspace.evGx[138]*acadoWorkspace.x[2] + acadoWorkspace.evGx[139]*acadoWorkspace.x[3] + acadoWorkspace.d[34]; +acadoVariables.x[39] += + acadoWorkspace.evGx[140]*acadoWorkspace.x[0] + acadoWorkspace.evGx[141]*acadoWorkspace.x[1] + acadoWorkspace.evGx[142]*acadoWorkspace.x[2] + acadoWorkspace.evGx[143]*acadoWorkspace.x[3] + acadoWorkspace.d[35]; +acadoVariables.x[40] += + acadoWorkspace.evGx[144]*acadoWorkspace.x[0] + acadoWorkspace.evGx[145]*acadoWorkspace.x[1] + acadoWorkspace.evGx[146]*acadoWorkspace.x[2] + acadoWorkspace.evGx[147]*acadoWorkspace.x[3] + acadoWorkspace.d[36]; +acadoVariables.x[41] += + acadoWorkspace.evGx[148]*acadoWorkspace.x[0] + acadoWorkspace.evGx[149]*acadoWorkspace.x[1] + acadoWorkspace.evGx[150]*acadoWorkspace.x[2] + acadoWorkspace.evGx[151]*acadoWorkspace.x[3] + acadoWorkspace.d[37]; +acadoVariables.x[42] += + acadoWorkspace.evGx[152]*acadoWorkspace.x[0] + acadoWorkspace.evGx[153]*acadoWorkspace.x[1] + acadoWorkspace.evGx[154]*acadoWorkspace.x[2] + acadoWorkspace.evGx[155]*acadoWorkspace.x[3] + acadoWorkspace.d[38]; +acadoVariables.x[43] += + acadoWorkspace.evGx[156]*acadoWorkspace.x[0] + acadoWorkspace.evGx[157]*acadoWorkspace.x[1] + acadoWorkspace.evGx[158]*acadoWorkspace.x[2] + acadoWorkspace.evGx[159]*acadoWorkspace.x[3] + acadoWorkspace.d[39]; +acadoVariables.x[44] += + acadoWorkspace.evGx[160]*acadoWorkspace.x[0] + acadoWorkspace.evGx[161]*acadoWorkspace.x[1] + acadoWorkspace.evGx[162]*acadoWorkspace.x[2] + acadoWorkspace.evGx[163]*acadoWorkspace.x[3] + acadoWorkspace.d[40]; +acadoVariables.x[45] += + acadoWorkspace.evGx[164]*acadoWorkspace.x[0] + acadoWorkspace.evGx[165]*acadoWorkspace.x[1] + acadoWorkspace.evGx[166]*acadoWorkspace.x[2] + acadoWorkspace.evGx[167]*acadoWorkspace.x[3] + acadoWorkspace.d[41]; +acadoVariables.x[46] += + acadoWorkspace.evGx[168]*acadoWorkspace.x[0] + acadoWorkspace.evGx[169]*acadoWorkspace.x[1] + acadoWorkspace.evGx[170]*acadoWorkspace.x[2] + acadoWorkspace.evGx[171]*acadoWorkspace.x[3] + acadoWorkspace.d[42]; +acadoVariables.x[47] += + acadoWorkspace.evGx[172]*acadoWorkspace.x[0] + acadoWorkspace.evGx[173]*acadoWorkspace.x[1] + acadoWorkspace.evGx[174]*acadoWorkspace.x[2] + acadoWorkspace.evGx[175]*acadoWorkspace.x[3] + acadoWorkspace.d[43]; +acadoVariables.x[48] += + acadoWorkspace.evGx[176]*acadoWorkspace.x[0] + acadoWorkspace.evGx[177]*acadoWorkspace.x[1] + acadoWorkspace.evGx[178]*acadoWorkspace.x[2] + acadoWorkspace.evGx[179]*acadoWorkspace.x[3] + acadoWorkspace.d[44]; +acadoVariables.x[49] += + acadoWorkspace.evGx[180]*acadoWorkspace.x[0] + acadoWorkspace.evGx[181]*acadoWorkspace.x[1] + acadoWorkspace.evGx[182]*acadoWorkspace.x[2] + acadoWorkspace.evGx[183]*acadoWorkspace.x[3] + acadoWorkspace.d[45]; +acadoVariables.x[50] += + acadoWorkspace.evGx[184]*acadoWorkspace.x[0] + acadoWorkspace.evGx[185]*acadoWorkspace.x[1] + acadoWorkspace.evGx[186]*acadoWorkspace.x[2] + acadoWorkspace.evGx[187]*acadoWorkspace.x[3] + acadoWorkspace.d[46]; +acadoVariables.x[51] += + acadoWorkspace.evGx[188]*acadoWorkspace.x[0] + acadoWorkspace.evGx[189]*acadoWorkspace.x[1] + acadoWorkspace.evGx[190]*acadoWorkspace.x[2] + acadoWorkspace.evGx[191]*acadoWorkspace.x[3] + acadoWorkspace.d[47]; +acadoVariables.x[52] += + acadoWorkspace.evGx[192]*acadoWorkspace.x[0] + acadoWorkspace.evGx[193]*acadoWorkspace.x[1] + acadoWorkspace.evGx[194]*acadoWorkspace.x[2] + acadoWorkspace.evGx[195]*acadoWorkspace.x[3] + acadoWorkspace.d[48]; +acadoVariables.x[53] += + acadoWorkspace.evGx[196]*acadoWorkspace.x[0] + acadoWorkspace.evGx[197]*acadoWorkspace.x[1] + acadoWorkspace.evGx[198]*acadoWorkspace.x[2] + acadoWorkspace.evGx[199]*acadoWorkspace.x[3] + acadoWorkspace.d[49]; +acadoVariables.x[54] += + acadoWorkspace.evGx[200]*acadoWorkspace.x[0] + acadoWorkspace.evGx[201]*acadoWorkspace.x[1] + acadoWorkspace.evGx[202]*acadoWorkspace.x[2] + acadoWorkspace.evGx[203]*acadoWorkspace.x[3] + acadoWorkspace.d[50]; +acadoVariables.x[55] += + acadoWorkspace.evGx[204]*acadoWorkspace.x[0] + acadoWorkspace.evGx[205]*acadoWorkspace.x[1] + acadoWorkspace.evGx[206]*acadoWorkspace.x[2] + acadoWorkspace.evGx[207]*acadoWorkspace.x[3] + acadoWorkspace.d[51]; +acadoVariables.x[56] += + acadoWorkspace.evGx[208]*acadoWorkspace.x[0] + acadoWorkspace.evGx[209]*acadoWorkspace.x[1] + acadoWorkspace.evGx[210]*acadoWorkspace.x[2] + acadoWorkspace.evGx[211]*acadoWorkspace.x[3] + acadoWorkspace.d[52]; +acadoVariables.x[57] += + acadoWorkspace.evGx[212]*acadoWorkspace.x[0] + acadoWorkspace.evGx[213]*acadoWorkspace.x[1] + acadoWorkspace.evGx[214]*acadoWorkspace.x[2] + acadoWorkspace.evGx[215]*acadoWorkspace.x[3] + acadoWorkspace.d[53]; +acadoVariables.x[58] += + acadoWorkspace.evGx[216]*acadoWorkspace.x[0] + acadoWorkspace.evGx[217]*acadoWorkspace.x[1] + acadoWorkspace.evGx[218]*acadoWorkspace.x[2] + acadoWorkspace.evGx[219]*acadoWorkspace.x[3] + acadoWorkspace.d[54]; +acadoVariables.x[59] += + acadoWorkspace.evGx[220]*acadoWorkspace.x[0] + acadoWorkspace.evGx[221]*acadoWorkspace.x[1] + acadoWorkspace.evGx[222]*acadoWorkspace.x[2] + acadoWorkspace.evGx[223]*acadoWorkspace.x[3] + acadoWorkspace.d[55]; +acadoVariables.x[60] += + acadoWorkspace.evGx[224]*acadoWorkspace.x[0] + acadoWorkspace.evGx[225]*acadoWorkspace.x[1] + acadoWorkspace.evGx[226]*acadoWorkspace.x[2] + acadoWorkspace.evGx[227]*acadoWorkspace.x[3] + acadoWorkspace.d[56]; +acadoVariables.x[61] += + acadoWorkspace.evGx[228]*acadoWorkspace.x[0] + acadoWorkspace.evGx[229]*acadoWorkspace.x[1] + acadoWorkspace.evGx[230]*acadoWorkspace.x[2] + acadoWorkspace.evGx[231]*acadoWorkspace.x[3] + acadoWorkspace.d[57]; +acadoVariables.x[62] += + acadoWorkspace.evGx[232]*acadoWorkspace.x[0] + acadoWorkspace.evGx[233]*acadoWorkspace.x[1] + acadoWorkspace.evGx[234]*acadoWorkspace.x[2] + acadoWorkspace.evGx[235]*acadoWorkspace.x[3] + acadoWorkspace.d[58]; +acadoVariables.x[63] += + acadoWorkspace.evGx[236]*acadoWorkspace.x[0] + acadoWorkspace.evGx[237]*acadoWorkspace.x[1] + acadoWorkspace.evGx[238]*acadoWorkspace.x[2] + acadoWorkspace.evGx[239]*acadoWorkspace.x[3] + acadoWorkspace.d[59]; +acadoVariables.x[64] += + acadoWorkspace.evGx[240]*acadoWorkspace.x[0] + acadoWorkspace.evGx[241]*acadoWorkspace.x[1] + acadoWorkspace.evGx[242]*acadoWorkspace.x[2] + acadoWorkspace.evGx[243]*acadoWorkspace.x[3] + acadoWorkspace.d[60]; +acadoVariables.x[65] += + acadoWorkspace.evGx[244]*acadoWorkspace.x[0] + acadoWorkspace.evGx[245]*acadoWorkspace.x[1] + acadoWorkspace.evGx[246]*acadoWorkspace.x[2] + acadoWorkspace.evGx[247]*acadoWorkspace.x[3] + acadoWorkspace.d[61]; +acadoVariables.x[66] += + acadoWorkspace.evGx[248]*acadoWorkspace.x[0] + acadoWorkspace.evGx[249]*acadoWorkspace.x[1] + acadoWorkspace.evGx[250]*acadoWorkspace.x[2] + acadoWorkspace.evGx[251]*acadoWorkspace.x[3] + acadoWorkspace.d[62]; +acadoVariables.x[67] += + acadoWorkspace.evGx[252]*acadoWorkspace.x[0] + acadoWorkspace.evGx[253]*acadoWorkspace.x[1] + acadoWorkspace.evGx[254]*acadoWorkspace.x[2] + acadoWorkspace.evGx[255]*acadoWorkspace.x[3] + acadoWorkspace.d[63]; +acadoVariables.x[68] += + acadoWorkspace.evGx[256]*acadoWorkspace.x[0] + acadoWorkspace.evGx[257]*acadoWorkspace.x[1] + acadoWorkspace.evGx[258]*acadoWorkspace.x[2] + acadoWorkspace.evGx[259]*acadoWorkspace.x[3] + acadoWorkspace.d[64]; +acadoVariables.x[69] += + acadoWorkspace.evGx[260]*acadoWorkspace.x[0] + acadoWorkspace.evGx[261]*acadoWorkspace.x[1] + acadoWorkspace.evGx[262]*acadoWorkspace.x[2] + acadoWorkspace.evGx[263]*acadoWorkspace.x[3] + acadoWorkspace.d[65]; +acadoVariables.x[70] += + acadoWorkspace.evGx[264]*acadoWorkspace.x[0] + acadoWorkspace.evGx[265]*acadoWorkspace.x[1] + acadoWorkspace.evGx[266]*acadoWorkspace.x[2] + acadoWorkspace.evGx[267]*acadoWorkspace.x[3] + acadoWorkspace.d[66]; +acadoVariables.x[71] += + acadoWorkspace.evGx[268]*acadoWorkspace.x[0] + acadoWorkspace.evGx[269]*acadoWorkspace.x[1] + acadoWorkspace.evGx[270]*acadoWorkspace.x[2] + acadoWorkspace.evGx[271]*acadoWorkspace.x[3] + acadoWorkspace.d[67]; +acadoVariables.x[72] += + acadoWorkspace.evGx[272]*acadoWorkspace.x[0] + acadoWorkspace.evGx[273]*acadoWorkspace.x[1] + acadoWorkspace.evGx[274]*acadoWorkspace.x[2] + acadoWorkspace.evGx[275]*acadoWorkspace.x[3] + acadoWorkspace.d[68]; +acadoVariables.x[73] += + acadoWorkspace.evGx[276]*acadoWorkspace.x[0] + acadoWorkspace.evGx[277]*acadoWorkspace.x[1] + acadoWorkspace.evGx[278]*acadoWorkspace.x[2] + acadoWorkspace.evGx[279]*acadoWorkspace.x[3] + acadoWorkspace.d[69]; +acadoVariables.x[74] += + acadoWorkspace.evGx[280]*acadoWorkspace.x[0] + acadoWorkspace.evGx[281]*acadoWorkspace.x[1] + acadoWorkspace.evGx[282]*acadoWorkspace.x[2] + acadoWorkspace.evGx[283]*acadoWorkspace.x[3] + acadoWorkspace.d[70]; +acadoVariables.x[75] += + acadoWorkspace.evGx[284]*acadoWorkspace.x[0] + acadoWorkspace.evGx[285]*acadoWorkspace.x[1] + acadoWorkspace.evGx[286]*acadoWorkspace.x[2] + acadoWorkspace.evGx[287]*acadoWorkspace.x[3] + acadoWorkspace.d[71]; +acadoVariables.x[76] += + acadoWorkspace.evGx[288]*acadoWorkspace.x[0] + acadoWorkspace.evGx[289]*acadoWorkspace.x[1] + acadoWorkspace.evGx[290]*acadoWorkspace.x[2] + acadoWorkspace.evGx[291]*acadoWorkspace.x[3] + acadoWorkspace.d[72]; +acadoVariables.x[77] += + acadoWorkspace.evGx[292]*acadoWorkspace.x[0] + acadoWorkspace.evGx[293]*acadoWorkspace.x[1] + acadoWorkspace.evGx[294]*acadoWorkspace.x[2] + acadoWorkspace.evGx[295]*acadoWorkspace.x[3] + acadoWorkspace.d[73]; +acadoVariables.x[78] += + acadoWorkspace.evGx[296]*acadoWorkspace.x[0] + acadoWorkspace.evGx[297]*acadoWorkspace.x[1] + acadoWorkspace.evGx[298]*acadoWorkspace.x[2] + acadoWorkspace.evGx[299]*acadoWorkspace.x[3] + acadoWorkspace.d[74]; +acadoVariables.x[79] += + acadoWorkspace.evGx[300]*acadoWorkspace.x[0] + acadoWorkspace.evGx[301]*acadoWorkspace.x[1] + acadoWorkspace.evGx[302]*acadoWorkspace.x[2] + acadoWorkspace.evGx[303]*acadoWorkspace.x[3] + acadoWorkspace.d[75]; +acadoVariables.x[80] += + acadoWorkspace.evGx[304]*acadoWorkspace.x[0] + acadoWorkspace.evGx[305]*acadoWorkspace.x[1] + acadoWorkspace.evGx[306]*acadoWorkspace.x[2] + acadoWorkspace.evGx[307]*acadoWorkspace.x[3] + acadoWorkspace.d[76]; +acadoVariables.x[81] += + acadoWorkspace.evGx[308]*acadoWorkspace.x[0] + acadoWorkspace.evGx[309]*acadoWorkspace.x[1] + acadoWorkspace.evGx[310]*acadoWorkspace.x[2] + acadoWorkspace.evGx[311]*acadoWorkspace.x[3] + acadoWorkspace.d[77]; +acadoVariables.x[82] += + acadoWorkspace.evGx[312]*acadoWorkspace.x[0] + acadoWorkspace.evGx[313]*acadoWorkspace.x[1] + acadoWorkspace.evGx[314]*acadoWorkspace.x[2] + acadoWorkspace.evGx[315]*acadoWorkspace.x[3] + acadoWorkspace.d[78]; +acadoVariables.x[83] += + acadoWorkspace.evGx[316]*acadoWorkspace.x[0] + acadoWorkspace.evGx[317]*acadoWorkspace.x[1] + acadoWorkspace.evGx[318]*acadoWorkspace.x[2] + acadoWorkspace.evGx[319]*acadoWorkspace.x[3] + acadoWorkspace.d[79]; +acadoVariables.x[84] += + acadoWorkspace.evGx[320]*acadoWorkspace.x[0] + acadoWorkspace.evGx[321]*acadoWorkspace.x[1] + acadoWorkspace.evGx[322]*acadoWorkspace.x[2] + acadoWorkspace.evGx[323]*acadoWorkspace.x[3] + acadoWorkspace.d[80]; +acadoVariables.x[85] += + acadoWorkspace.evGx[324]*acadoWorkspace.x[0] + acadoWorkspace.evGx[325]*acadoWorkspace.x[1] + acadoWorkspace.evGx[326]*acadoWorkspace.x[2] + acadoWorkspace.evGx[327]*acadoWorkspace.x[3] + acadoWorkspace.d[81]; +acadoVariables.x[86] += + acadoWorkspace.evGx[328]*acadoWorkspace.x[0] + acadoWorkspace.evGx[329]*acadoWorkspace.x[1] + acadoWorkspace.evGx[330]*acadoWorkspace.x[2] + acadoWorkspace.evGx[331]*acadoWorkspace.x[3] + acadoWorkspace.d[82]; +acadoVariables.x[87] += + acadoWorkspace.evGx[332]*acadoWorkspace.x[0] + acadoWorkspace.evGx[333]*acadoWorkspace.x[1] + acadoWorkspace.evGx[334]*acadoWorkspace.x[2] + acadoWorkspace.evGx[335]*acadoWorkspace.x[3] + acadoWorkspace.d[83]; +acadoVariables.x[88] += + acadoWorkspace.evGx[336]*acadoWorkspace.x[0] + acadoWorkspace.evGx[337]*acadoWorkspace.x[1] + acadoWorkspace.evGx[338]*acadoWorkspace.x[2] + acadoWorkspace.evGx[339]*acadoWorkspace.x[3] + acadoWorkspace.d[84]; +acadoVariables.x[89] += + acadoWorkspace.evGx[340]*acadoWorkspace.x[0] + acadoWorkspace.evGx[341]*acadoWorkspace.x[1] + acadoWorkspace.evGx[342]*acadoWorkspace.x[2] + acadoWorkspace.evGx[343]*acadoWorkspace.x[3] + acadoWorkspace.d[85]; +acadoVariables.x[90] += + acadoWorkspace.evGx[344]*acadoWorkspace.x[0] + acadoWorkspace.evGx[345]*acadoWorkspace.x[1] + acadoWorkspace.evGx[346]*acadoWorkspace.x[2] + acadoWorkspace.evGx[347]*acadoWorkspace.x[3] + acadoWorkspace.d[86]; +acadoVariables.x[91] += + acadoWorkspace.evGx[348]*acadoWorkspace.x[0] + acadoWorkspace.evGx[349]*acadoWorkspace.x[1] + acadoWorkspace.evGx[350]*acadoWorkspace.x[2] + acadoWorkspace.evGx[351]*acadoWorkspace.x[3] + acadoWorkspace.d[87]; +acadoVariables.x[92] += + acadoWorkspace.evGx[352]*acadoWorkspace.x[0] + acadoWorkspace.evGx[353]*acadoWorkspace.x[1] + acadoWorkspace.evGx[354]*acadoWorkspace.x[2] + acadoWorkspace.evGx[355]*acadoWorkspace.x[3] + acadoWorkspace.d[88]; +acadoVariables.x[93] += + acadoWorkspace.evGx[356]*acadoWorkspace.x[0] + acadoWorkspace.evGx[357]*acadoWorkspace.x[1] + acadoWorkspace.evGx[358]*acadoWorkspace.x[2] + acadoWorkspace.evGx[359]*acadoWorkspace.x[3] + acadoWorkspace.d[89]; +acadoVariables.x[94] += + acadoWorkspace.evGx[360]*acadoWorkspace.x[0] + acadoWorkspace.evGx[361]*acadoWorkspace.x[1] + acadoWorkspace.evGx[362]*acadoWorkspace.x[2] + acadoWorkspace.evGx[363]*acadoWorkspace.x[3] + acadoWorkspace.d[90]; +acadoVariables.x[95] += + acadoWorkspace.evGx[364]*acadoWorkspace.x[0] + acadoWorkspace.evGx[365]*acadoWorkspace.x[1] + acadoWorkspace.evGx[366]*acadoWorkspace.x[2] + acadoWorkspace.evGx[367]*acadoWorkspace.x[3] + acadoWorkspace.d[91]; +acadoVariables.x[96] += + acadoWorkspace.evGx[368]*acadoWorkspace.x[0] + acadoWorkspace.evGx[369]*acadoWorkspace.x[1] + acadoWorkspace.evGx[370]*acadoWorkspace.x[2] + acadoWorkspace.evGx[371]*acadoWorkspace.x[3] + acadoWorkspace.d[92]; +acadoVariables.x[97] += + acadoWorkspace.evGx[372]*acadoWorkspace.x[0] + acadoWorkspace.evGx[373]*acadoWorkspace.x[1] + acadoWorkspace.evGx[374]*acadoWorkspace.x[2] + acadoWorkspace.evGx[375]*acadoWorkspace.x[3] + acadoWorkspace.d[93]; +acadoVariables.x[98] += + acadoWorkspace.evGx[376]*acadoWorkspace.x[0] + acadoWorkspace.evGx[377]*acadoWorkspace.x[1] + acadoWorkspace.evGx[378]*acadoWorkspace.x[2] + acadoWorkspace.evGx[379]*acadoWorkspace.x[3] + acadoWorkspace.d[94]; +acadoVariables.x[99] += + acadoWorkspace.evGx[380]*acadoWorkspace.x[0] + acadoWorkspace.evGx[381]*acadoWorkspace.x[1] + acadoWorkspace.evGx[382]*acadoWorkspace.x[2] + acadoWorkspace.evGx[383]*acadoWorkspace.x[3] + acadoWorkspace.d[95]; +acadoVariables.x[100] += + acadoWorkspace.evGx[384]*acadoWorkspace.x[0] + acadoWorkspace.evGx[385]*acadoWorkspace.x[1] + acadoWorkspace.evGx[386]*acadoWorkspace.x[2] + acadoWorkspace.evGx[387]*acadoWorkspace.x[3] + acadoWorkspace.d[96]; +acadoVariables.x[101] += + acadoWorkspace.evGx[388]*acadoWorkspace.x[0] + acadoWorkspace.evGx[389]*acadoWorkspace.x[1] + acadoWorkspace.evGx[390]*acadoWorkspace.x[2] + acadoWorkspace.evGx[391]*acadoWorkspace.x[3] + acadoWorkspace.d[97]; +acadoVariables.x[102] += + acadoWorkspace.evGx[392]*acadoWorkspace.x[0] + acadoWorkspace.evGx[393]*acadoWorkspace.x[1] + acadoWorkspace.evGx[394]*acadoWorkspace.x[2] + acadoWorkspace.evGx[395]*acadoWorkspace.x[3] + acadoWorkspace.d[98]; +acadoVariables.x[103] += + acadoWorkspace.evGx[396]*acadoWorkspace.x[0] + acadoWorkspace.evGx[397]*acadoWorkspace.x[1] + acadoWorkspace.evGx[398]*acadoWorkspace.x[2] + acadoWorkspace.evGx[399]*acadoWorkspace.x[3] + acadoWorkspace.d[99]; +acadoVariables.x[104] += + acadoWorkspace.evGx[400]*acadoWorkspace.x[0] + acadoWorkspace.evGx[401]*acadoWorkspace.x[1] + acadoWorkspace.evGx[402]*acadoWorkspace.x[2] + acadoWorkspace.evGx[403]*acadoWorkspace.x[3] + acadoWorkspace.d[100]; +acadoVariables.x[105] += + acadoWorkspace.evGx[404]*acadoWorkspace.x[0] + acadoWorkspace.evGx[405]*acadoWorkspace.x[1] + acadoWorkspace.evGx[406]*acadoWorkspace.x[2] + acadoWorkspace.evGx[407]*acadoWorkspace.x[3] + acadoWorkspace.d[101]; +acadoVariables.x[106] += + acadoWorkspace.evGx[408]*acadoWorkspace.x[0] + acadoWorkspace.evGx[409]*acadoWorkspace.x[1] + acadoWorkspace.evGx[410]*acadoWorkspace.x[2] + acadoWorkspace.evGx[411]*acadoWorkspace.x[3] + acadoWorkspace.d[102]; +acadoVariables.x[107] += + acadoWorkspace.evGx[412]*acadoWorkspace.x[0] + acadoWorkspace.evGx[413]*acadoWorkspace.x[1] + acadoWorkspace.evGx[414]*acadoWorkspace.x[2] + acadoWorkspace.evGx[415]*acadoWorkspace.x[3] + acadoWorkspace.d[103]; +acadoVariables.x[108] += + acadoWorkspace.evGx[416]*acadoWorkspace.x[0] + acadoWorkspace.evGx[417]*acadoWorkspace.x[1] + acadoWorkspace.evGx[418]*acadoWorkspace.x[2] + acadoWorkspace.evGx[419]*acadoWorkspace.x[3] + acadoWorkspace.d[104]; +acadoVariables.x[109] += + acadoWorkspace.evGx[420]*acadoWorkspace.x[0] + acadoWorkspace.evGx[421]*acadoWorkspace.x[1] + acadoWorkspace.evGx[422]*acadoWorkspace.x[2] + acadoWorkspace.evGx[423]*acadoWorkspace.x[3] + acadoWorkspace.d[105]; +acadoVariables.x[110] += + acadoWorkspace.evGx[424]*acadoWorkspace.x[0] + acadoWorkspace.evGx[425]*acadoWorkspace.x[1] + acadoWorkspace.evGx[426]*acadoWorkspace.x[2] + acadoWorkspace.evGx[427]*acadoWorkspace.x[3] + acadoWorkspace.d[106]; +acadoVariables.x[111] += + acadoWorkspace.evGx[428]*acadoWorkspace.x[0] + acadoWorkspace.evGx[429]*acadoWorkspace.x[1] + acadoWorkspace.evGx[430]*acadoWorkspace.x[2] + acadoWorkspace.evGx[431]*acadoWorkspace.x[3] + acadoWorkspace.d[107]; +acadoVariables.x[112] += + acadoWorkspace.evGx[432]*acadoWorkspace.x[0] + acadoWorkspace.evGx[433]*acadoWorkspace.x[1] + acadoWorkspace.evGx[434]*acadoWorkspace.x[2] + acadoWorkspace.evGx[435]*acadoWorkspace.x[3] + acadoWorkspace.d[108]; +acadoVariables.x[113] += + acadoWorkspace.evGx[436]*acadoWorkspace.x[0] + acadoWorkspace.evGx[437]*acadoWorkspace.x[1] + acadoWorkspace.evGx[438]*acadoWorkspace.x[2] + acadoWorkspace.evGx[439]*acadoWorkspace.x[3] + acadoWorkspace.d[109]; +acadoVariables.x[114] += + acadoWorkspace.evGx[440]*acadoWorkspace.x[0] + acadoWorkspace.evGx[441]*acadoWorkspace.x[1] + acadoWorkspace.evGx[442]*acadoWorkspace.x[2] + acadoWorkspace.evGx[443]*acadoWorkspace.x[3] + acadoWorkspace.d[110]; +acadoVariables.x[115] += + acadoWorkspace.evGx[444]*acadoWorkspace.x[0] + acadoWorkspace.evGx[445]*acadoWorkspace.x[1] + acadoWorkspace.evGx[446]*acadoWorkspace.x[2] + acadoWorkspace.evGx[447]*acadoWorkspace.x[3] + acadoWorkspace.d[111]; +acadoVariables.x[116] += + acadoWorkspace.evGx[448]*acadoWorkspace.x[0] + acadoWorkspace.evGx[449]*acadoWorkspace.x[1] + acadoWorkspace.evGx[450]*acadoWorkspace.x[2] + acadoWorkspace.evGx[451]*acadoWorkspace.x[3] + acadoWorkspace.d[112]; +acadoVariables.x[117] += + acadoWorkspace.evGx[452]*acadoWorkspace.x[0] + acadoWorkspace.evGx[453]*acadoWorkspace.x[1] + acadoWorkspace.evGx[454]*acadoWorkspace.x[2] + acadoWorkspace.evGx[455]*acadoWorkspace.x[3] + acadoWorkspace.d[113]; +acadoVariables.x[118] += + acadoWorkspace.evGx[456]*acadoWorkspace.x[0] + acadoWorkspace.evGx[457]*acadoWorkspace.x[1] + acadoWorkspace.evGx[458]*acadoWorkspace.x[2] + acadoWorkspace.evGx[459]*acadoWorkspace.x[3] + acadoWorkspace.d[114]; +acadoVariables.x[119] += + acadoWorkspace.evGx[460]*acadoWorkspace.x[0] + acadoWorkspace.evGx[461]*acadoWorkspace.x[1] + acadoWorkspace.evGx[462]*acadoWorkspace.x[2] + acadoWorkspace.evGx[463]*acadoWorkspace.x[3] + acadoWorkspace.d[115]; +acadoVariables.x[120] += + acadoWorkspace.evGx[464]*acadoWorkspace.x[0] + acadoWorkspace.evGx[465]*acadoWorkspace.x[1] + acadoWorkspace.evGx[466]*acadoWorkspace.x[2] + acadoWorkspace.evGx[467]*acadoWorkspace.x[3] + acadoWorkspace.d[116]; +acadoVariables.x[121] += + acadoWorkspace.evGx[468]*acadoWorkspace.x[0] + acadoWorkspace.evGx[469]*acadoWorkspace.x[1] + acadoWorkspace.evGx[470]*acadoWorkspace.x[2] + acadoWorkspace.evGx[471]*acadoWorkspace.x[3] + acadoWorkspace.d[117]; +acadoVariables.x[122] += + acadoWorkspace.evGx[472]*acadoWorkspace.x[0] + acadoWorkspace.evGx[473]*acadoWorkspace.x[1] + acadoWorkspace.evGx[474]*acadoWorkspace.x[2] + acadoWorkspace.evGx[475]*acadoWorkspace.x[3] + acadoWorkspace.d[118]; +acadoVariables.x[123] += + acadoWorkspace.evGx[476]*acadoWorkspace.x[0] + acadoWorkspace.evGx[477]*acadoWorkspace.x[1] + acadoWorkspace.evGx[478]*acadoWorkspace.x[2] + acadoWorkspace.evGx[479]*acadoWorkspace.x[3] + acadoWorkspace.d[119]; +acadoVariables.x[124] += + acadoWorkspace.evGx[480]*acadoWorkspace.x[0] + acadoWorkspace.evGx[481]*acadoWorkspace.x[1] + acadoWorkspace.evGx[482]*acadoWorkspace.x[2] + acadoWorkspace.evGx[483]*acadoWorkspace.x[3] + acadoWorkspace.d[120]; +acadoVariables.x[125] += + acadoWorkspace.evGx[484]*acadoWorkspace.x[0] + acadoWorkspace.evGx[485]*acadoWorkspace.x[1] + acadoWorkspace.evGx[486]*acadoWorkspace.x[2] + acadoWorkspace.evGx[487]*acadoWorkspace.x[3] + acadoWorkspace.d[121]; +acadoVariables.x[126] += + acadoWorkspace.evGx[488]*acadoWorkspace.x[0] + acadoWorkspace.evGx[489]*acadoWorkspace.x[1] + acadoWorkspace.evGx[490]*acadoWorkspace.x[2] + acadoWorkspace.evGx[491]*acadoWorkspace.x[3] + acadoWorkspace.d[122]; +acadoVariables.x[127] += + acadoWorkspace.evGx[492]*acadoWorkspace.x[0] + acadoWorkspace.evGx[493]*acadoWorkspace.x[1] + acadoWorkspace.evGx[494]*acadoWorkspace.x[2] + acadoWorkspace.evGx[495]*acadoWorkspace.x[3] + acadoWorkspace.d[123]; +acadoVariables.x[128] += + acadoWorkspace.evGx[496]*acadoWorkspace.x[0] + acadoWorkspace.evGx[497]*acadoWorkspace.x[1] + acadoWorkspace.evGx[498]*acadoWorkspace.x[2] + acadoWorkspace.evGx[499]*acadoWorkspace.x[3] + acadoWorkspace.d[124]; +acadoVariables.x[129] += + acadoWorkspace.evGx[500]*acadoWorkspace.x[0] + acadoWorkspace.evGx[501]*acadoWorkspace.x[1] + acadoWorkspace.evGx[502]*acadoWorkspace.x[2] + acadoWorkspace.evGx[503]*acadoWorkspace.x[3] + acadoWorkspace.d[125]; +acadoVariables.x[130] += + acadoWorkspace.evGx[504]*acadoWorkspace.x[0] + acadoWorkspace.evGx[505]*acadoWorkspace.x[1] + acadoWorkspace.evGx[506]*acadoWorkspace.x[2] + acadoWorkspace.evGx[507]*acadoWorkspace.x[3] + acadoWorkspace.d[126]; +acadoVariables.x[131] += + acadoWorkspace.evGx[508]*acadoWorkspace.x[0] + acadoWorkspace.evGx[509]*acadoWorkspace.x[1] + acadoWorkspace.evGx[510]*acadoWorkspace.x[2] + acadoWorkspace.evGx[511]*acadoWorkspace.x[3] + acadoWorkspace.d[127]; + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +for (lRun2 = 0; lRun2 < lRun1 + 1; ++lRun2) +{ +lRun3 = (((lRun1 + 1) * (lRun1)) / (2)) + (lRun2); +acado_multEDu( &(acadoWorkspace.E[ lRun3 * 8 ]), &(acadoWorkspace.x[ lRun2 * 2 + 4 ]), &(acadoVariables.x[ lRun1 * 4 + 4 ]) ); +} +} +} + +int acado_preparationStep( ) +{ +int ret; + +ret = acado_modelSimulation(); +acado_evaluateObjective( ); +acado_condensePrep( ); +return ret; +} + +int acado_feedbackStep( ) +{ +int tmp; + +acado_condenseFdb( ); + +tmp = acado_solve( ); + +acado_expand( ); +return tmp; +} + +int acado_initializeSolver( ) +{ +int ret; + +/* This is a function which must be called once before any other function call! */ + + +ret = 0; + +memset(&acadoWorkspace, 0, sizeof( acadoWorkspace )); +return ret; +} + +void acado_initializeNodesByForwardSimulation( ) +{ +int index; +for (index = 0; index < 32; ++index) +{ +acadoWorkspace.state[0] = acadoVariables.x[index * 4]; +acadoWorkspace.state[1] = acadoVariables.x[index * 4 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[index * 4 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[index * 4 + 3]; +acadoWorkspace.state[28] = acadoVariables.u[index * 2]; +acadoWorkspace.state[29] = acadoVariables.u[index * 2 + 1]; +acadoWorkspace.state[30] = acadoVariables.od[index * 2]; +acadoWorkspace.state[31] = acadoVariables.od[index * 2 + 1]; + +acado_integrate(acadoWorkspace.state, index == 0, index); + +acadoVariables.x[index * 4 + 4] = acadoWorkspace.state[0]; +acadoVariables.x[index * 4 + 5] = acadoWorkspace.state[1]; +acadoVariables.x[index * 4 + 6] = acadoWorkspace.state[2]; +acadoVariables.x[index * 4 + 7] = acadoWorkspace.state[3]; +} +} + +void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ) +{ +int index; +for (index = 0; index < 32; ++index) +{ +acadoVariables.x[index * 4] = acadoVariables.x[index * 4 + 4]; +acadoVariables.x[index * 4 + 1] = acadoVariables.x[index * 4 + 5]; +acadoVariables.x[index * 4 + 2] = acadoVariables.x[index * 4 + 6]; +acadoVariables.x[index * 4 + 3] = acadoVariables.x[index * 4 + 7]; +} + +if (strategy == 1 && xEnd != 0) +{ +acadoVariables.x[128] = xEnd[0]; +acadoVariables.x[129] = xEnd[1]; +acadoVariables.x[130] = xEnd[2]; +acadoVariables.x[131] = xEnd[3]; +} +else if (strategy == 2) +{ +acadoWorkspace.state[0] = acadoVariables.x[128]; +acadoWorkspace.state[1] = acadoVariables.x[129]; +acadoWorkspace.state[2] = acadoVariables.x[130]; +acadoWorkspace.state[3] = acadoVariables.x[131]; +if (uEnd != 0) +{ +acadoWorkspace.state[28] = uEnd[0]; +acadoWorkspace.state[29] = uEnd[1]; +} +else +{ +acadoWorkspace.state[28] = acadoVariables.u[62]; +acadoWorkspace.state[29] = acadoVariables.u[63]; +} +acadoWorkspace.state[30] = acadoVariables.od[64]; +acadoWorkspace.state[31] = acadoVariables.od[65]; + +acado_integrate(acadoWorkspace.state, 1, 31); + +acadoVariables.x[128] = acadoWorkspace.state[0]; +acadoVariables.x[129] = acadoWorkspace.state[1]; +acadoVariables.x[130] = acadoWorkspace.state[2]; +acadoVariables.x[131] = acadoWorkspace.state[3]; +} +} + +void acado_shiftControls( real_t* const uEnd ) +{ +int index; +for (index = 0; index < 31; ++index) +{ +acadoVariables.u[index * 2] = acadoVariables.u[index * 2 + 2]; +acadoVariables.u[index * 2 + 1] = acadoVariables.u[index * 2 + 3]; +} + +if (uEnd != 0) +{ +acadoVariables.u[62] = uEnd[0]; +acadoVariables.u[63] = uEnd[1]; +} +} + +real_t acado_getKKT( ) +{ +real_t kkt; + +int index; +real_t prd; + +kkt = + acadoWorkspace.g[0]*acadoWorkspace.x[0] + acadoWorkspace.g[1]*acadoWorkspace.x[1] + acadoWorkspace.g[2]*acadoWorkspace.x[2] + acadoWorkspace.g[3]*acadoWorkspace.x[3] + acadoWorkspace.g[4]*acadoWorkspace.x[4] + acadoWorkspace.g[5]*acadoWorkspace.x[5] + acadoWorkspace.g[6]*acadoWorkspace.x[6] + acadoWorkspace.g[7]*acadoWorkspace.x[7] + acadoWorkspace.g[8]*acadoWorkspace.x[8] + acadoWorkspace.g[9]*acadoWorkspace.x[9] + acadoWorkspace.g[10]*acadoWorkspace.x[10] + acadoWorkspace.g[11]*acadoWorkspace.x[11] + acadoWorkspace.g[12]*acadoWorkspace.x[12] + acadoWorkspace.g[13]*acadoWorkspace.x[13] + acadoWorkspace.g[14]*acadoWorkspace.x[14] + acadoWorkspace.g[15]*acadoWorkspace.x[15] + acadoWorkspace.g[16]*acadoWorkspace.x[16] + acadoWorkspace.g[17]*acadoWorkspace.x[17] + acadoWorkspace.g[18]*acadoWorkspace.x[18] + acadoWorkspace.g[19]*acadoWorkspace.x[19] + acadoWorkspace.g[20]*acadoWorkspace.x[20] + acadoWorkspace.g[21]*acadoWorkspace.x[21] + acadoWorkspace.g[22]*acadoWorkspace.x[22] + acadoWorkspace.g[23]*acadoWorkspace.x[23] + acadoWorkspace.g[24]*acadoWorkspace.x[24] + acadoWorkspace.g[25]*acadoWorkspace.x[25] + acadoWorkspace.g[26]*acadoWorkspace.x[26] + acadoWorkspace.g[27]*acadoWorkspace.x[27] + acadoWorkspace.g[28]*acadoWorkspace.x[28] + acadoWorkspace.g[29]*acadoWorkspace.x[29] + acadoWorkspace.g[30]*acadoWorkspace.x[30] + acadoWorkspace.g[31]*acadoWorkspace.x[31] + acadoWorkspace.g[32]*acadoWorkspace.x[32] + acadoWorkspace.g[33]*acadoWorkspace.x[33] + acadoWorkspace.g[34]*acadoWorkspace.x[34] + acadoWorkspace.g[35]*acadoWorkspace.x[35] + acadoWorkspace.g[36]*acadoWorkspace.x[36] + acadoWorkspace.g[37]*acadoWorkspace.x[37] + acadoWorkspace.g[38]*acadoWorkspace.x[38] + acadoWorkspace.g[39]*acadoWorkspace.x[39] + acadoWorkspace.g[40]*acadoWorkspace.x[40] + acadoWorkspace.g[41]*acadoWorkspace.x[41] + acadoWorkspace.g[42]*acadoWorkspace.x[42] + acadoWorkspace.g[43]*acadoWorkspace.x[43] + acadoWorkspace.g[44]*acadoWorkspace.x[44] + acadoWorkspace.g[45]*acadoWorkspace.x[45] + acadoWorkspace.g[46]*acadoWorkspace.x[46] + acadoWorkspace.g[47]*acadoWorkspace.x[47] + acadoWorkspace.g[48]*acadoWorkspace.x[48] + acadoWorkspace.g[49]*acadoWorkspace.x[49] + acadoWorkspace.g[50]*acadoWorkspace.x[50] + acadoWorkspace.g[51]*acadoWorkspace.x[51] + acadoWorkspace.g[52]*acadoWorkspace.x[52] + acadoWorkspace.g[53]*acadoWorkspace.x[53] + acadoWorkspace.g[54]*acadoWorkspace.x[54] + acadoWorkspace.g[55]*acadoWorkspace.x[55] + acadoWorkspace.g[56]*acadoWorkspace.x[56] + acadoWorkspace.g[57]*acadoWorkspace.x[57] + acadoWorkspace.g[58]*acadoWorkspace.x[58] + acadoWorkspace.g[59]*acadoWorkspace.x[59] + acadoWorkspace.g[60]*acadoWorkspace.x[60] + acadoWorkspace.g[61]*acadoWorkspace.x[61] + acadoWorkspace.g[62]*acadoWorkspace.x[62] + acadoWorkspace.g[63]*acadoWorkspace.x[63] + acadoWorkspace.g[64]*acadoWorkspace.x[64] + acadoWorkspace.g[65]*acadoWorkspace.x[65] + acadoWorkspace.g[66]*acadoWorkspace.x[66] + acadoWorkspace.g[67]*acadoWorkspace.x[67]; +kkt = fabs( kkt ); +for (index = 0; index < 68; ++index) +{ +prd = acadoWorkspace.y[index]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lb[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ub[index] * prd); +} +for (index = 0; index < 96; ++index) +{ +prd = acadoWorkspace.y[index + 68]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lbA[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ubA[index] * prd); +} +return kkt; +} + +real_t acado_getObjective( ) +{ +real_t objVal; + +int lRun1; +/** Row vector of size: 5 */ +real_t tmpDy[ 5 ]; + +/** Row vector of size: 3 */ +real_t tmpDyN[ 3 ]; + +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[lRun1 * 4]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[lRun1 * 4 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[lRun1 * 4 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[lRun1 * 4 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.u[lRun1 * 2]; +acadoWorkspace.objValueIn[5] = acadoVariables.u[lRun1 * 2 + 1]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[lRun1 * 2]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1 * 2 + 1]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.Dy[lRun1 * 5] = acadoWorkspace.objValueOut[0] - acadoVariables.y[lRun1 * 5]; +acadoWorkspace.Dy[lRun1 * 5 + 1] = acadoWorkspace.objValueOut[1] - acadoVariables.y[lRun1 * 5 + 1]; +acadoWorkspace.Dy[lRun1 * 5 + 2] = acadoWorkspace.objValueOut[2] - acadoVariables.y[lRun1 * 5 + 2]; +acadoWorkspace.Dy[lRun1 * 5 + 3] = acadoWorkspace.objValueOut[3] - acadoVariables.y[lRun1 * 5 + 3]; +acadoWorkspace.Dy[lRun1 * 5 + 4] = acadoWorkspace.objValueOut[4] - acadoVariables.y[lRun1 * 5 + 4]; +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[128]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[129]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[130]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[131]; +acadoWorkspace.objValueIn[4] = acadoVariables.od[64]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[65]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0] - acadoVariables.yN[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1] - acadoVariables.yN[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2] - acadoVariables.yN[2]; +objVal = 0.0000000000000000e+00; +for (lRun1 = 0; lRun1 < 32; ++lRun1) +{ +tmpDy[0] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 5] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 10] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 15] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 20]; +tmpDy[1] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 1] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 6] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 11] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 16] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 21]; +tmpDy[2] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 2] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 7] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 12] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 17] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 22]; +tmpDy[3] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 3] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 8] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 13] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 18] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 23]; +tmpDy[4] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 4] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 9] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 14] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 19] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 24]; +objVal += + acadoWorkspace.Dy[lRun1 * 5]*tmpDy[0] + acadoWorkspace.Dy[lRun1 * 5 + 1]*tmpDy[1] + acadoWorkspace.Dy[lRun1 * 5 + 2]*tmpDy[2] + acadoWorkspace.Dy[lRun1 * 5 + 3]*tmpDy[3] + acadoWorkspace.Dy[lRun1 * 5 + 4]*tmpDy[4]; +} + +tmpDyN[0] = + acadoWorkspace.DyN[0]*acadoVariables.WN[0] + acadoWorkspace.DyN[1]*acadoVariables.WN[3] + acadoWorkspace.DyN[2]*acadoVariables.WN[6]; +tmpDyN[1] = + acadoWorkspace.DyN[0]*acadoVariables.WN[1] + acadoWorkspace.DyN[1]*acadoVariables.WN[4] + acadoWorkspace.DyN[2]*acadoVariables.WN[7]; +tmpDyN[2] = + acadoWorkspace.DyN[0]*acadoVariables.WN[2] + acadoWorkspace.DyN[1]*acadoVariables.WN[5] + acadoWorkspace.DyN[2]*acadoVariables.WN[8]; +objVal += + acadoWorkspace.DyN[0]*tmpDyN[0] + acadoWorkspace.DyN[1]*tmpDyN[1] + acadoWorkspace.DyN[2]*tmpDyN[2]; + +objVal *= 0.5; +return objVal; +} + diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/libmpc_py.py b/selfdrive/controls/lib/longitudinal_mpc_lib/libmpc_py.py new file mode 100644 index 000000000..3b15b08fe --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/libmpc_py.py @@ -0,0 +1,34 @@ +import os + +from cffi import FFI +from common.ffi_wrapper import suffix + +mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__))) +libmpc_fn = os.path.join(mpc_dir, "libmpc"+suffix()) + +ffi = FFI() +ffi.cdef(""" +const int MPC_N = 32; + +typedef struct { +double x_ego, v_ego, a_ego; +} state_t; + + +typedef struct { +double x_ego[MPC_N+1]; +double v_ego[MPC_N+1]; +double a_ego[MPC_N+1]; +double t[MPC_N+1]; +double j_ego[MPC_N]; +double cost; +} log_t; + + +void init(double xCost, double vCost, double aCost, double jerkCost, double constraintCost); +int run_mpc(state_t * x0, log_t * solution, + double target_x[MPC_N+1], double target_v[MPC_N+1], double target_a[MPC_N+1], + double min_a, double max_a); +""") + +libmpc = ffi.dlopen(libmpc_fn) diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/longitudinal_mpc.c b/selfdrive/controls/lib/longitudinal_mpc_lib/longitudinal_mpc.c similarity index 55% rename from selfdrive/controls/lib/longitudinal_mpc_model/longitudinal_mpc.c rename to selfdrive/controls/lib/longitudinal_mpc_lib/longitudinal_mpc.c index 39cff8f2a..c392609da 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_model/longitudinal_mpc.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/longitudinal_mpc.c @@ -1,5 +1,6 @@ #include "acado_common.h" #include "acado_auxiliary_functions.h" +#include "common/modeldata.h" #include #include @@ -31,7 +32,7 @@ typedef struct { double cost; } log_t; -void init(double xCost, double vCost, double aCost, double accelCost, double jerkCost){ +void init(double xCost, double vCost, double aCost, double jerkCost, double constraintCost){ acado_initializeSolver(); int i; const int STEP_MULTIPLIER = 3; @@ -46,91 +47,57 @@ void init(double xCost, double vCost, double aCost, double accelCost, double jer /* MPC: initialize the current state feedback. */ for (i = 0; i < NX; ++i) acadoVariables.x0[ i ] = 0.0; + // Set weights - for (i = 0; i < N; i++) { - int f = 1; - if (i > 4){ - f = STEP_MULTIPLIER; - } + double f = 20 * (T_IDXS[i+1] - T_IDXS[i]); // Setup diagonal entries acadoVariables.W[NY*NY*i + (NY+1)*0] = xCost * f; acadoVariables.W[NY*NY*i + (NY+1)*1] = vCost * f; acadoVariables.W[NY*NY*i + (NY+1)*2] = aCost * f; - acadoVariables.W[NY*NY*i + (NY+1)*3] = accelCost * f; - acadoVariables.W[NY*NY*i + (NY+1)*4] = jerkCost * f; + acadoVariables.W[NY*NY*i + (NY+1)*3] = jerkCost * f; + acadoVariables.W[NY*NY*i + (NY+1)*4] = constraintCost * f; } acadoVariables.WN[(NYN+1)*0] = xCost * STEP_MULTIPLIER; acadoVariables.WN[(NYN+1)*1] = vCost * STEP_MULTIPLIER; acadoVariables.WN[(NYN+1)*2] = aCost * STEP_MULTIPLIER; - acadoVariables.WN[(NYN+1)*3] = accelCost * STEP_MULTIPLIER; } -void init_with_simulation(double v_ego){ - int i; - - double x_ego = 0.0; - - double dt = 0.2; - double t = 0.0; - - for (i = 0; i < N + 1; ++i){ - if (i > 4){ - dt = 0.6; - } - - acadoVariables.x[i*NX] = x_ego; - acadoVariables.x[i*NX+1] = v_ego; - acadoVariables.x[i*NX+2] = 0; - acadoVariables.x[i*NX+3] = t; - - x_ego += v_ego * dt; - t += dt; - } - - for (i = 0; i < NU * N; ++i) acadoVariables.u[ i ] = 0.0; - for (i = 0; i < NY * N; ++i) acadoVariables.y[ i ] = 0.0; - for (i = 0; i < NYN; ++i) acadoVariables.yN[ i ] = 0.0; -} int run_mpc(state_t * x0, log_t * solution, - double x_poly[4], double v_poly[4], double a_poly[4]){ + double target_x[N+1], double target_v[N+1], double target_a[N+1], + double min_a, double max_a){ int i; - for (i = 0; i < N + 1; ++i){ - acadoVariables.od[i*NOD+0] = x_poly[0]; - acadoVariables.od[i*NOD+1] = x_poly[1]; - acadoVariables.od[i*NOD+2] = x_poly[2]; - acadoVariables.od[i*NOD+3] = x_poly[3]; - - acadoVariables.od[i*NOD+4] = v_poly[0]; - acadoVariables.od[i*NOD+5] = v_poly[1]; - acadoVariables.od[i*NOD+6] = v_poly[2]; - acadoVariables.od[i*NOD+7] = v_poly[3]; - - acadoVariables.od[i*NOD+8] = a_poly[0]; - acadoVariables.od[i*NOD+9] = a_poly[1]; - acadoVariables.od[i*NOD+10] = a_poly[2]; - acadoVariables.od[i*NOD+11] = a_poly[3]; + acadoVariables.od[i*NOD] = min_a; + acadoVariables.od[i*NOD+1] = max_a; } + for (i = 0; i < N; i+= 1){ + acadoVariables.y[NY*i + 0] = target_x[i]; + acadoVariables.y[NY*i + 1] = target_v[i]; + acadoVariables.y[NY*i + 2] = target_a[i]; + acadoVariables.y[NY*i + 3] = 0.0; + acadoVariables.y[NY*i + 4] = 0.0; + } + acadoVariables.yN[0] = target_x[N]; + acadoVariables.yN[1] = target_v[N]; + acadoVariables.yN[2] = target_a[N]; - acadoVariables.x[0] = acadoVariables.x0[0] = x0->x_ego; - acadoVariables.x[1] = acadoVariables.x0[1] = x0->v_ego; - acadoVariables.x[2] = acadoVariables.x0[2] = x0->a_ego; - acadoVariables.x[3] = acadoVariables.x0[3] = 0; + acadoVariables.x0[0] = x0->x_ego; + acadoVariables.x0[1] = x0->v_ego; + acadoVariables.x0[2] = x0->a_ego; acado_preparationStep(); acado_feedbackStep(); - for (i = 0; i <= N; i++){ + for (i = 0; i <= N; i++) { solution->x_ego[i] = acadoVariables.x[i*NX]; solution->v_ego[i] = acadoVariables.x[i*NX+1]; solution->a_ego[i] = acadoVariables.x[i*NX+2]; - solution->t[i] = acadoVariables.x[i*NX+3]; - if (i < N){ - solution->j_ego[i] = acadoVariables.u[i]; + if (i < N) { + solution->j_ego[i] = acadoVariables.u[i*NU]; } } solution->cost = acado_getObjective(); diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/SConscript b/selfdrive/controls/lib/longitudinal_mpc_model/SConscript deleted file mode 100644 index f474bf798..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_model/SConscript +++ /dev/null @@ -1,31 +0,0 @@ -Import('env', 'arch') - - -cpp_path = [ - "#phonelibs/acado/include", - "#phonelibs/acado/include/acado", - "#phonelibs/qpoases/INCLUDE", - "#phonelibs/qpoases/INCLUDE/EXTRAS", - "#phonelibs/qpoases/SRC/", - "#phonelibs/qpoases", - "lib_mpc_export" - -] - -mpc_files = [ - "longitudinal_mpc.c", - Glob("lib_mpc_export/*.c"), - Glob("lib_mpc_export/*.cpp"), -] - -interface_dir = Dir('lib_mpc_export') - -SConscript(['#phonelibs/qpoases/SConscript'], variant_dir='lib_qp', exports=['interface_dir']) - -env.SharedLibrary('mpc', mpc_files, LIBS=['m', 'qpoases'], LIBPATH=['lib_qp'], CPPPATH=cpp_path) - -# if arch != "aarch64": -# acado_libs = [File("#phonelibs/acado/x64/lib/libacado_toolkit.a"), -# File("#phonelibs/acado/x64/lib/libacado_casadi.a"), -# File("#phonelibs/acado/x64/lib/libacado_csparse.a")] -# env.Program('generator', 'generator.cpp', LIBS=acado_libs, CPPPATH=cpp_path) diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/generator.cpp b/selfdrive/controls/lib/longitudinal_mpc_model/generator.cpp deleted file mode 100644 index 129b52a76..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_model/generator.cpp +++ /dev/null @@ -1,99 +0,0 @@ -#include - -const int controlHorizon = 50; - -using namespace std; - - -int main( ) -{ - USING_NAMESPACE_ACADO - - - DifferentialEquation f; - - DifferentialState x_ego, v_ego, a_ego, t; - - OnlineData x_poly_r0, x_poly_r1, x_poly_r2, x_poly_r3; - OnlineData v_poly_r0, v_poly_r1, v_poly_r2, v_poly_r3; - OnlineData a_poly_r0, a_poly_r1, a_poly_r2, a_poly_r3; - - Control j_ego; - - // Equations of motion - f << dot(x_ego) == v_ego; - f << dot(v_ego) == a_ego; - f << dot(a_ego) == j_ego; - f << dot(t) == 1; - - auto poly_x = x_poly_r0*(t*t*t) + x_poly_r1*(t*t) + x_poly_r2*t + x_poly_r3; - auto poly_v = v_poly_r0*(t*t*t) + v_poly_r1*(t*t) + v_poly_r2*t + v_poly_r3; - auto poly_a = a_poly_r0*(t*t*t) + a_poly_r1*(t*t) + a_poly_r2*t + a_poly_r3; - - // Running cost - Function h; - h << x_ego - poly_x; - h << v_ego - poly_v; - h << a_ego - poly_a; - h << a_ego * (0.1 * v_ego + 1.0); - h << j_ego * (0.1 * v_ego + 1.0); - - // Weights are defined in mpc. - BMatrix Q(5,5); Q.setAll(true); - - // Terminal cost - Function hN; - hN << x_ego - poly_x; - hN << v_ego - poly_v; - hN << a_ego - poly_a; - hN << a_ego * (0.1 * v_ego + 1.0); - - // Weights are defined in mpc. - BMatrix QN(4,4); QN.setAll(true); - - // Non uniform time grid - // First 5 timesteps are 0.2, after that it's 0.6 - DMatrix numSteps(20, 1); - for (int i = 0; i < 5; i++){ - numSteps(i) = 1; - } - for (int i = 5; i < 20; i++){ - numSteps(i) = 3; - } - - // Setup Optimal Control Problem - const double tStart = 0.0; - const double tEnd = 10.0; - - OCP ocp( tStart, tEnd, numSteps); - ocp.subjectTo(f); - - ocp.minimizeLSQ(Q, h); - ocp.minimizeLSQEndTerm(QN, hN); - - //ocp.subjectTo( 0.0 <= v_ego); - ocp.setNOD(12); - - OCPexport mpc(ocp); - mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); - mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); - mpc.set( INTEGRATOR_TYPE, INT_RK4 ); - mpc.set( NUM_INTEGRATOR_STEPS, controlHorizon); - mpc.set( MAX_NUM_QP_ITERATIONS, 500); - mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); - - mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); - mpc.set( QP_SOLVER, QP_QPOASES ); - mpc.set( HOTSTART_QP, YES ); - mpc.set( GENERATE_TEST_FILE, NO); - mpc.set( GENERATE_MAKE_FILE, NO ); - mpc.set( GENERATE_MATLAB_INTERFACE, NO ); - mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); - - if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) - exit( EXIT_FAILURE ); - - mpc.printDimensionsQP( ); - - return EXIT_SUCCESS; -} diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_integrator.c b/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_integrator.c deleted file mode 100644 index 7212295f9..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_integrator.c +++ /dev/null @@ -1,231 +0,0 @@ -/* - * This file was auto-generated using the ACADO Toolkit. - * - * While ACADO Toolkit is free software released under the terms of - * the GNU Lesser General Public License (LGPL), the generated code - * as such remains the property of the user who used ACADO Toolkit - * to generate this code. In particular, user dependent data of the code - * do not inherit the GNU LGPL license. On the other hand, parts of the - * generated code that are a direct copy of source code from the - * ACADO Toolkit or the software tools it is based on, remain, as derived - * work, automatically covered by the LGPL license. - * - * ACADO Toolkit is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * - */ - - -#include "acado_common.h" - - -void acado_rhs_forw(const real_t* in, real_t* out) -{ -const real_t* xd = in; -const real_t* u = in + 24; - -/* Compute outputs: */ -out[0] = xd[1]; -out[1] = xd[2]; -out[2] = u[0]; -out[3] = (real_t)(1.0000000000000000e+00); -out[4] = xd[8]; -out[5] = xd[9]; -out[6] = xd[10]; -out[7] = xd[11]; -out[8] = xd[12]; -out[9] = xd[13]; -out[10] = xd[14]; -out[11] = xd[15]; -out[12] = (real_t)(0.0000000000000000e+00); -out[13] = (real_t)(0.0000000000000000e+00); -out[14] = (real_t)(0.0000000000000000e+00); -out[15] = (real_t)(0.0000000000000000e+00); -out[16] = (real_t)(0.0000000000000000e+00); -out[17] = (real_t)(0.0000000000000000e+00); -out[18] = (real_t)(0.0000000000000000e+00); -out[19] = (real_t)(0.0000000000000000e+00); -out[20] = xd[21]; -out[21] = xd[22]; -out[22] = (real_t)(1.0000000000000000e+00); -out[23] = (real_t)(0.0000000000000000e+00); -} - -/* Fixed step size:0.2 */ -int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ) -{ -int error; - -int run1; -int numSteps[20] = {1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3}; -int numInts = numSteps[rk_index]; -acadoWorkspace.rk_ttt = 0.0000000000000000e+00; -rk_eta[4] = 1.0000000000000000e+00; -rk_eta[5] = 0.0000000000000000e+00; -rk_eta[6] = 0.0000000000000000e+00; -rk_eta[7] = 0.0000000000000000e+00; -rk_eta[8] = 0.0000000000000000e+00; -rk_eta[9] = 1.0000000000000000e+00; -rk_eta[10] = 0.0000000000000000e+00; -rk_eta[11] = 0.0000000000000000e+00; -rk_eta[12] = 0.0000000000000000e+00; -rk_eta[13] = 0.0000000000000000e+00; -rk_eta[14] = 1.0000000000000000e+00; -rk_eta[15] = 0.0000000000000000e+00; -rk_eta[16] = 0.0000000000000000e+00; -rk_eta[17] = 0.0000000000000000e+00; -rk_eta[18] = 0.0000000000000000e+00; -rk_eta[19] = 1.0000000000000000e+00; -rk_eta[20] = 0.0000000000000000e+00; -rk_eta[21] = 0.0000000000000000e+00; -rk_eta[22] = 0.0000000000000000e+00; -rk_eta[23] = 0.0000000000000000e+00; -acadoWorkspace.rk_xxx[24] = rk_eta[24]; -acadoWorkspace.rk_xxx[25] = rk_eta[25]; -acadoWorkspace.rk_xxx[26] = rk_eta[26]; -acadoWorkspace.rk_xxx[27] = rk_eta[27]; -acadoWorkspace.rk_xxx[28] = rk_eta[28]; -acadoWorkspace.rk_xxx[29] = rk_eta[29]; -acadoWorkspace.rk_xxx[30] = rk_eta[30]; -acadoWorkspace.rk_xxx[31] = rk_eta[31]; -acadoWorkspace.rk_xxx[32] = rk_eta[32]; -acadoWorkspace.rk_xxx[33] = rk_eta[33]; -acadoWorkspace.rk_xxx[34] = rk_eta[34]; -acadoWorkspace.rk_xxx[35] = rk_eta[35]; -acadoWorkspace.rk_xxx[36] = rk_eta[36]; - -for (run1 = 0; run1 < 1; ++run1) -{ -for(run1 = 0; run1 < numInts; run1++ ) { -acadoWorkspace.rk_xxx[0] = + rk_eta[0]; -acadoWorkspace.rk_xxx[1] = + rk_eta[1]; -acadoWorkspace.rk_xxx[2] = + rk_eta[2]; -acadoWorkspace.rk_xxx[3] = + rk_eta[3]; -acadoWorkspace.rk_xxx[4] = + rk_eta[4]; -acadoWorkspace.rk_xxx[5] = + rk_eta[5]; -acadoWorkspace.rk_xxx[6] = + rk_eta[6]; -acadoWorkspace.rk_xxx[7] = + rk_eta[7]; -acadoWorkspace.rk_xxx[8] = + rk_eta[8]; -acadoWorkspace.rk_xxx[9] = + rk_eta[9]; -acadoWorkspace.rk_xxx[10] = + rk_eta[10]; -acadoWorkspace.rk_xxx[11] = + rk_eta[11]; -acadoWorkspace.rk_xxx[12] = + rk_eta[12]; -acadoWorkspace.rk_xxx[13] = + rk_eta[13]; -acadoWorkspace.rk_xxx[14] = + rk_eta[14]; -acadoWorkspace.rk_xxx[15] = + rk_eta[15]; -acadoWorkspace.rk_xxx[16] = + rk_eta[16]; -acadoWorkspace.rk_xxx[17] = + rk_eta[17]; -acadoWorkspace.rk_xxx[18] = + rk_eta[18]; -acadoWorkspace.rk_xxx[19] = + rk_eta[19]; -acadoWorkspace.rk_xxx[20] = + rk_eta[20]; -acadoWorkspace.rk_xxx[21] = + rk_eta[21]; -acadoWorkspace.rk_xxx[22] = + rk_eta[22]; -acadoWorkspace.rk_xxx[23] = + rk_eta[23]; -acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); -acadoWorkspace.rk_xxx[0] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[0] + rk_eta[0]; -acadoWorkspace.rk_xxx[1] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[1] + rk_eta[1]; -acadoWorkspace.rk_xxx[2] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[2] + rk_eta[2]; -acadoWorkspace.rk_xxx[3] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[3] + rk_eta[3]; -acadoWorkspace.rk_xxx[4] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[4] + rk_eta[4]; -acadoWorkspace.rk_xxx[5] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[5] + rk_eta[5]; -acadoWorkspace.rk_xxx[6] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[6] + rk_eta[6]; -acadoWorkspace.rk_xxx[7] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[7] + rk_eta[7]; -acadoWorkspace.rk_xxx[8] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[8] + rk_eta[8]; -acadoWorkspace.rk_xxx[9] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[9] + rk_eta[9]; -acadoWorkspace.rk_xxx[10] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[10] + rk_eta[10]; -acadoWorkspace.rk_xxx[11] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[11] + rk_eta[11]; -acadoWorkspace.rk_xxx[12] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[12] + rk_eta[12]; -acadoWorkspace.rk_xxx[13] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[13] + rk_eta[13]; -acadoWorkspace.rk_xxx[14] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[14] + rk_eta[14]; -acadoWorkspace.rk_xxx[15] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[15] + rk_eta[15]; -acadoWorkspace.rk_xxx[16] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[16] + rk_eta[16]; -acadoWorkspace.rk_xxx[17] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[17] + rk_eta[17]; -acadoWorkspace.rk_xxx[18] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[18] + rk_eta[18]; -acadoWorkspace.rk_xxx[19] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[19] + rk_eta[19]; -acadoWorkspace.rk_xxx[20] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[20] + rk_eta[20]; -acadoWorkspace.rk_xxx[21] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[21] + rk_eta[21]; -acadoWorkspace.rk_xxx[22] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[22] + rk_eta[22]; -acadoWorkspace.rk_xxx[23] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[23] + rk_eta[23]; -acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 24 ]) ); -acadoWorkspace.rk_xxx[0] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[24] + rk_eta[0]; -acadoWorkspace.rk_xxx[1] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[25] + rk_eta[1]; -acadoWorkspace.rk_xxx[2] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[26] + rk_eta[2]; -acadoWorkspace.rk_xxx[3] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[27] + rk_eta[3]; -acadoWorkspace.rk_xxx[4] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[28] + rk_eta[4]; -acadoWorkspace.rk_xxx[5] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[29] + rk_eta[5]; -acadoWorkspace.rk_xxx[6] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[30] + rk_eta[6]; -acadoWorkspace.rk_xxx[7] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[31] + rk_eta[7]; -acadoWorkspace.rk_xxx[8] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[32] + rk_eta[8]; -acadoWorkspace.rk_xxx[9] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[33] + rk_eta[9]; -acadoWorkspace.rk_xxx[10] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[34] + rk_eta[10]; -acadoWorkspace.rk_xxx[11] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[35] + rk_eta[11]; -acadoWorkspace.rk_xxx[12] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[36] + rk_eta[12]; -acadoWorkspace.rk_xxx[13] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[37] + rk_eta[13]; -acadoWorkspace.rk_xxx[14] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[38] + rk_eta[14]; -acadoWorkspace.rk_xxx[15] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[39] + rk_eta[15]; -acadoWorkspace.rk_xxx[16] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[40] + rk_eta[16]; -acadoWorkspace.rk_xxx[17] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[41] + rk_eta[17]; -acadoWorkspace.rk_xxx[18] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[42] + rk_eta[18]; -acadoWorkspace.rk_xxx[19] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[43] + rk_eta[19]; -acadoWorkspace.rk_xxx[20] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[44] + rk_eta[20]; -acadoWorkspace.rk_xxx[21] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[45] + rk_eta[21]; -acadoWorkspace.rk_xxx[22] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[46] + rk_eta[22]; -acadoWorkspace.rk_xxx[23] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[47] + rk_eta[23]; -acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 48 ]) ); -acadoWorkspace.rk_xxx[0] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[48] + rk_eta[0]; -acadoWorkspace.rk_xxx[1] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[49] + rk_eta[1]; -acadoWorkspace.rk_xxx[2] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[50] + rk_eta[2]; -acadoWorkspace.rk_xxx[3] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[51] + rk_eta[3]; -acadoWorkspace.rk_xxx[4] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[52] + rk_eta[4]; -acadoWorkspace.rk_xxx[5] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[53] + rk_eta[5]; -acadoWorkspace.rk_xxx[6] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[54] + rk_eta[6]; -acadoWorkspace.rk_xxx[7] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[55] + rk_eta[7]; -acadoWorkspace.rk_xxx[8] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[56] + rk_eta[8]; -acadoWorkspace.rk_xxx[9] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[57] + rk_eta[9]; -acadoWorkspace.rk_xxx[10] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[58] + rk_eta[10]; -acadoWorkspace.rk_xxx[11] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[59] + rk_eta[11]; -acadoWorkspace.rk_xxx[12] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[60] + rk_eta[12]; -acadoWorkspace.rk_xxx[13] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[61] + rk_eta[13]; -acadoWorkspace.rk_xxx[14] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[62] + rk_eta[14]; -acadoWorkspace.rk_xxx[15] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[63] + rk_eta[15]; -acadoWorkspace.rk_xxx[16] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[64] + rk_eta[16]; -acadoWorkspace.rk_xxx[17] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[65] + rk_eta[17]; -acadoWorkspace.rk_xxx[18] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[66] + rk_eta[18]; -acadoWorkspace.rk_xxx[19] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[67] + rk_eta[19]; -acadoWorkspace.rk_xxx[20] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[68] + rk_eta[20]; -acadoWorkspace.rk_xxx[21] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[69] + rk_eta[21]; -acadoWorkspace.rk_xxx[22] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[70] + rk_eta[22]; -acadoWorkspace.rk_xxx[23] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[71] + rk_eta[23]; -acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 72 ]) ); -rk_eta[0] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[0] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[24] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[48] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[72]; -rk_eta[1] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[1] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[25] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[49] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[73]; -rk_eta[2] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[2] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[26] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[50] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[74]; -rk_eta[3] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[3] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[27] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[51] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[75]; -rk_eta[4] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[4] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[28] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[52] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[76]; -rk_eta[5] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[5] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[29] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[53] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[77]; -rk_eta[6] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[6] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[30] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[54] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[78]; -rk_eta[7] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[7] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[31] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[55] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[79]; -rk_eta[8] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[8] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[32] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[56] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[80]; -rk_eta[9] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[9] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[33] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[57] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[81]; -rk_eta[10] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[10] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[34] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[58] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[82]; -rk_eta[11] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[11] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[35] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[59] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[83]; -rk_eta[12] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[12] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[36] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[60] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[84]; -rk_eta[13] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[13] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[37] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[61] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[85]; -rk_eta[14] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[14] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[38] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[62] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[86]; -rk_eta[15] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[15] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[39] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[63] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[87]; -rk_eta[16] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[16] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[40] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[64] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[88]; -rk_eta[17] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[17] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[41] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[65] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[89]; -rk_eta[18] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[18] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[42] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[66] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[90]; -rk_eta[19] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[19] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[43] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[67] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[91]; -rk_eta[20] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[20] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[44] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[68] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[92]; -rk_eta[21] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[21] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[45] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[69] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[93]; -rk_eta[22] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[22] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[46] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[70] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[94]; -rk_eta[23] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[23] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[47] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[71] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[95]; -acadoWorkspace.rk_ttt += 1.0000000000000000e+00; -} -} -error = 0; -return error; -} - diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_solver.c b/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_solver.c deleted file mode 100644 index 411d47b60..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/acado_solver.c +++ /dev/null @@ -1,4944 +0,0 @@ -/* - * This file was auto-generated using the ACADO Toolkit. - * - * While ACADO Toolkit is free software released under the terms of - * the GNU Lesser General Public License (LGPL), the generated code - * as such remains the property of the user who used ACADO Toolkit - * to generate this code. In particular, user dependent data of the code - * do not inherit the GNU LGPL license. On the other hand, parts of the - * generated code that are a direct copy of source code from the - * ACADO Toolkit or the software tools it is based on, remain, as derived - * work, automatically covered by the LGPL license. - * - * ACADO Toolkit is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * - */ - - -#include "acado_common.h" - - - - -/******************************************************************************/ -/* */ -/* ACADO code generation */ -/* */ -/******************************************************************************/ - - -int acado_modelSimulation( ) -{ -int ret; - -int lRun1; -ret = 0; -for (lRun1 = 0; lRun1 < 20; ++lRun1) -{ -acadoWorkspace.state[0] = acadoVariables.x[lRun1 * 4]; -acadoWorkspace.state[1] = acadoVariables.x[lRun1 * 4 + 1]; -acadoWorkspace.state[2] = acadoVariables.x[lRun1 * 4 + 2]; -acadoWorkspace.state[3] = acadoVariables.x[lRun1 * 4 + 3]; - -acadoWorkspace.state[24] = acadoVariables.u[lRun1]; -acadoWorkspace.state[25] = acadoVariables.od[lRun1 * 12]; -acadoWorkspace.state[26] = acadoVariables.od[lRun1 * 12 + 1]; -acadoWorkspace.state[27] = acadoVariables.od[lRun1 * 12 + 2]; -acadoWorkspace.state[28] = acadoVariables.od[lRun1 * 12 + 3]; -acadoWorkspace.state[29] = acadoVariables.od[lRun1 * 12 + 4]; -acadoWorkspace.state[30] = acadoVariables.od[lRun1 * 12 + 5]; -acadoWorkspace.state[31] = acadoVariables.od[lRun1 * 12 + 6]; -acadoWorkspace.state[32] = acadoVariables.od[lRun1 * 12 + 7]; -acadoWorkspace.state[33] = acadoVariables.od[lRun1 * 12 + 8]; -acadoWorkspace.state[34] = acadoVariables.od[lRun1 * 12 + 9]; -acadoWorkspace.state[35] = acadoVariables.od[lRun1 * 12 + 10]; -acadoWorkspace.state[36] = acadoVariables.od[lRun1 * 12 + 11]; - -ret = acado_integrate(acadoWorkspace.state, 1, lRun1); - -acadoWorkspace.d[lRun1 * 4] = acadoWorkspace.state[0] - acadoVariables.x[lRun1 * 4 + 4]; -acadoWorkspace.d[lRun1 * 4 + 1] = acadoWorkspace.state[1] - acadoVariables.x[lRun1 * 4 + 5]; -acadoWorkspace.d[lRun1 * 4 + 2] = acadoWorkspace.state[2] - acadoVariables.x[lRun1 * 4 + 6]; -acadoWorkspace.d[lRun1 * 4 + 3] = acadoWorkspace.state[3] - acadoVariables.x[lRun1 * 4 + 7]; - -acadoWorkspace.evGx[lRun1 * 16] = acadoWorkspace.state[4]; -acadoWorkspace.evGx[lRun1 * 16 + 1] = acadoWorkspace.state[5]; -acadoWorkspace.evGx[lRun1 * 16 + 2] = acadoWorkspace.state[6]; -acadoWorkspace.evGx[lRun1 * 16 + 3] = acadoWorkspace.state[7]; -acadoWorkspace.evGx[lRun1 * 16 + 4] = acadoWorkspace.state[8]; -acadoWorkspace.evGx[lRun1 * 16 + 5] = acadoWorkspace.state[9]; -acadoWorkspace.evGx[lRun1 * 16 + 6] = acadoWorkspace.state[10]; -acadoWorkspace.evGx[lRun1 * 16 + 7] = acadoWorkspace.state[11]; -acadoWorkspace.evGx[lRun1 * 16 + 8] = acadoWorkspace.state[12]; -acadoWorkspace.evGx[lRun1 * 16 + 9] = acadoWorkspace.state[13]; -acadoWorkspace.evGx[lRun1 * 16 + 10] = acadoWorkspace.state[14]; -acadoWorkspace.evGx[lRun1 * 16 + 11] = acadoWorkspace.state[15]; -acadoWorkspace.evGx[lRun1 * 16 + 12] = acadoWorkspace.state[16]; -acadoWorkspace.evGx[lRun1 * 16 + 13] = acadoWorkspace.state[17]; -acadoWorkspace.evGx[lRun1 * 16 + 14] = acadoWorkspace.state[18]; -acadoWorkspace.evGx[lRun1 * 16 + 15] = acadoWorkspace.state[19]; - -acadoWorkspace.evGu[lRun1 * 4] = acadoWorkspace.state[20]; -acadoWorkspace.evGu[lRun1 * 4 + 1] = acadoWorkspace.state[21]; -acadoWorkspace.evGu[lRun1 * 4 + 2] = acadoWorkspace.state[22]; -acadoWorkspace.evGu[lRun1 * 4 + 3] = acadoWorkspace.state[23]; -} -return ret; -} - -void acado_evaluateLSQ(const real_t* in, real_t* out) -{ -const real_t* xd = in; -const real_t* u = in + 4; -const real_t* od = in + 5; - -/* Compute outputs: */ -out[0] = (xd[0]-((((od[0]*((xd[3]*xd[3])*xd[3]))+(od[1]*(xd[3]*xd[3])))+(od[2]*xd[3]))+od[3])); -out[1] = (xd[1]-((((od[4]*((xd[3]*xd[3])*xd[3]))+(od[5]*(xd[3]*xd[3])))+(od[6]*xd[3]))+od[7])); -out[2] = (xd[2]-((((od[8]*((xd[3]*xd[3])*xd[3]))+(od[9]*(xd[3]*xd[3])))+(od[10]*xd[3]))+od[11])); -out[3] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); -out[4] = (u[0]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); -out[5] = (real_t)(1.0000000000000000e+00); -out[6] = (real_t)(0.0000000000000000e+00); -out[7] = (real_t)(0.0000000000000000e+00); -out[8] = ((real_t)(0.0000000000000000e+00)-(((od[0]*(((xd[3]+xd[3])*xd[3])+(xd[3]*xd[3])))+(od[1]*(xd[3]+xd[3])))+od[2])); -out[9] = (real_t)(0.0000000000000000e+00); -out[10] = (real_t)(1.0000000000000000e+00); -out[11] = (real_t)(0.0000000000000000e+00); -out[12] = ((real_t)(0.0000000000000000e+00)-(((od[4]*(((xd[3]+xd[3])*xd[3])+(xd[3]*xd[3])))+(od[5]*(xd[3]+xd[3])))+od[6])); -out[13] = (real_t)(0.0000000000000000e+00); -out[14] = (real_t)(0.0000000000000000e+00); -out[15] = (real_t)(1.0000000000000000e+00); -out[16] = ((real_t)(0.0000000000000000e+00)-(((od[8]*(((xd[3]+xd[3])*xd[3])+(xd[3]*xd[3])))+(od[9]*(xd[3]+xd[3])))+od[10])); -out[17] = (real_t)(0.0000000000000000e+00); -out[18] = (xd[2]*(real_t)(1.0000000000000001e-01)); -out[19] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)); -out[20] = (real_t)(0.0000000000000000e+00); -out[21] = (real_t)(0.0000000000000000e+00); -out[22] = (u[0]*(real_t)(1.0000000000000001e-01)); -out[23] = (real_t)(0.0000000000000000e+00); -out[24] = (real_t)(0.0000000000000000e+00); -out[25] = (real_t)(0.0000000000000000e+00); -out[26] = (real_t)(0.0000000000000000e+00); -out[27] = (real_t)(0.0000000000000000e+00); -out[28] = (real_t)(0.0000000000000000e+00); -out[29] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)); -} - -void acado_evaluateLSQEndTerm(const real_t* in, real_t* out) -{ -const real_t* xd = in; -const real_t* od = in + 4; - -/* Compute outputs: */ -out[0] = (xd[0]-((((od[0]*((xd[3]*xd[3])*xd[3]))+(od[1]*(xd[3]*xd[3])))+(od[2]*xd[3]))+od[3])); -out[1] = (xd[1]-((((od[4]*((xd[3]*xd[3])*xd[3]))+(od[5]*(xd[3]*xd[3])))+(od[6]*xd[3]))+od[7])); -out[2] = (xd[2]-((((od[8]*((xd[3]*xd[3])*xd[3]))+(od[9]*(xd[3]*xd[3])))+(od[10]*xd[3]))+od[11])); -out[3] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); -out[4] = (real_t)(1.0000000000000000e+00); -out[5] = (real_t)(0.0000000000000000e+00); -out[6] = (real_t)(0.0000000000000000e+00); -out[7] = ((real_t)(0.0000000000000000e+00)-(((od[0]*(((xd[3]+xd[3])*xd[3])+(xd[3]*xd[3])))+(od[1]*(xd[3]+xd[3])))+od[2])); -out[8] = (real_t)(0.0000000000000000e+00); -out[9] = (real_t)(1.0000000000000000e+00); -out[10] = (real_t)(0.0000000000000000e+00); -out[11] = ((real_t)(0.0000000000000000e+00)-(((od[4]*(((xd[3]+xd[3])*xd[3])+(xd[3]*xd[3])))+(od[5]*(xd[3]+xd[3])))+od[6])); -out[12] = (real_t)(0.0000000000000000e+00); -out[13] = (real_t)(0.0000000000000000e+00); -out[14] = (real_t)(1.0000000000000000e+00); -out[15] = ((real_t)(0.0000000000000000e+00)-(((od[8]*(((xd[3]+xd[3])*xd[3])+(xd[3]*xd[3])))+(od[9]*(xd[3]+xd[3])))+od[10])); -out[16] = (real_t)(0.0000000000000000e+00); -out[17] = (xd[2]*(real_t)(1.0000000000000001e-01)); -out[18] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)); -out[19] = (real_t)(0.0000000000000000e+00); -} - -void acado_setObjQ1Q2( real_t* const tmpFx, real_t* const tmpObjS, real_t* const tmpQ1, real_t* const tmpQ2 ) -{ -tmpQ2[0] = + tmpFx[0]*tmpObjS[0] + tmpFx[4]*tmpObjS[5] + tmpFx[8]*tmpObjS[10] + tmpFx[12]*tmpObjS[15] + tmpFx[16]*tmpObjS[20]; -tmpQ2[1] = + tmpFx[0]*tmpObjS[1] + tmpFx[4]*tmpObjS[6] + tmpFx[8]*tmpObjS[11] + tmpFx[12]*tmpObjS[16] + tmpFx[16]*tmpObjS[21]; -tmpQ2[2] = + tmpFx[0]*tmpObjS[2] + tmpFx[4]*tmpObjS[7] + tmpFx[8]*tmpObjS[12] + tmpFx[12]*tmpObjS[17] + tmpFx[16]*tmpObjS[22]; -tmpQ2[3] = + tmpFx[0]*tmpObjS[3] + tmpFx[4]*tmpObjS[8] + tmpFx[8]*tmpObjS[13] + tmpFx[12]*tmpObjS[18] + tmpFx[16]*tmpObjS[23]; -tmpQ2[4] = + tmpFx[0]*tmpObjS[4] + tmpFx[4]*tmpObjS[9] + tmpFx[8]*tmpObjS[14] + tmpFx[12]*tmpObjS[19] + tmpFx[16]*tmpObjS[24]; -tmpQ2[5] = + tmpFx[1]*tmpObjS[0] + tmpFx[5]*tmpObjS[5] + tmpFx[9]*tmpObjS[10] + tmpFx[13]*tmpObjS[15] + tmpFx[17]*tmpObjS[20]; -tmpQ2[6] = + tmpFx[1]*tmpObjS[1] + tmpFx[5]*tmpObjS[6] + tmpFx[9]*tmpObjS[11] + tmpFx[13]*tmpObjS[16] + tmpFx[17]*tmpObjS[21]; -tmpQ2[7] = + tmpFx[1]*tmpObjS[2] + tmpFx[5]*tmpObjS[7] + tmpFx[9]*tmpObjS[12] + tmpFx[13]*tmpObjS[17] + tmpFx[17]*tmpObjS[22]; -tmpQ2[8] = + tmpFx[1]*tmpObjS[3] + tmpFx[5]*tmpObjS[8] + tmpFx[9]*tmpObjS[13] + tmpFx[13]*tmpObjS[18] + tmpFx[17]*tmpObjS[23]; -tmpQ2[9] = + tmpFx[1]*tmpObjS[4] + tmpFx[5]*tmpObjS[9] + tmpFx[9]*tmpObjS[14] + tmpFx[13]*tmpObjS[19] + tmpFx[17]*tmpObjS[24]; -tmpQ2[10] = + tmpFx[2]*tmpObjS[0] + tmpFx[6]*tmpObjS[5] + tmpFx[10]*tmpObjS[10] + tmpFx[14]*tmpObjS[15] + tmpFx[18]*tmpObjS[20]; -tmpQ2[11] = + tmpFx[2]*tmpObjS[1] + tmpFx[6]*tmpObjS[6] + tmpFx[10]*tmpObjS[11] + tmpFx[14]*tmpObjS[16] + tmpFx[18]*tmpObjS[21]; -tmpQ2[12] = + tmpFx[2]*tmpObjS[2] + tmpFx[6]*tmpObjS[7] + tmpFx[10]*tmpObjS[12] + tmpFx[14]*tmpObjS[17] + tmpFx[18]*tmpObjS[22]; -tmpQ2[13] = + tmpFx[2]*tmpObjS[3] + tmpFx[6]*tmpObjS[8] + tmpFx[10]*tmpObjS[13] + tmpFx[14]*tmpObjS[18] + tmpFx[18]*tmpObjS[23]; -tmpQ2[14] = + tmpFx[2]*tmpObjS[4] + tmpFx[6]*tmpObjS[9] + tmpFx[10]*tmpObjS[14] + tmpFx[14]*tmpObjS[19] + tmpFx[18]*tmpObjS[24]; -tmpQ2[15] = + tmpFx[3]*tmpObjS[0] + tmpFx[7]*tmpObjS[5] + tmpFx[11]*tmpObjS[10] + tmpFx[15]*tmpObjS[15] + tmpFx[19]*tmpObjS[20]; -tmpQ2[16] = + tmpFx[3]*tmpObjS[1] + tmpFx[7]*tmpObjS[6] + tmpFx[11]*tmpObjS[11] + tmpFx[15]*tmpObjS[16] + tmpFx[19]*tmpObjS[21]; -tmpQ2[17] = + tmpFx[3]*tmpObjS[2] + tmpFx[7]*tmpObjS[7] + tmpFx[11]*tmpObjS[12] + tmpFx[15]*tmpObjS[17] + tmpFx[19]*tmpObjS[22]; -tmpQ2[18] = + tmpFx[3]*tmpObjS[3] + tmpFx[7]*tmpObjS[8] + tmpFx[11]*tmpObjS[13] + tmpFx[15]*tmpObjS[18] + tmpFx[19]*tmpObjS[23]; -tmpQ2[19] = + tmpFx[3]*tmpObjS[4] + tmpFx[7]*tmpObjS[9] + tmpFx[11]*tmpObjS[14] + tmpFx[15]*tmpObjS[19] + tmpFx[19]*tmpObjS[24]; -tmpQ1[0] = + tmpQ2[0]*tmpFx[0] + tmpQ2[1]*tmpFx[4] + tmpQ2[2]*tmpFx[8] + tmpQ2[3]*tmpFx[12] + tmpQ2[4]*tmpFx[16]; -tmpQ1[1] = + tmpQ2[0]*tmpFx[1] + tmpQ2[1]*tmpFx[5] + tmpQ2[2]*tmpFx[9] + tmpQ2[3]*tmpFx[13] + tmpQ2[4]*tmpFx[17]; -tmpQ1[2] = + tmpQ2[0]*tmpFx[2] + tmpQ2[1]*tmpFx[6] + tmpQ2[2]*tmpFx[10] + tmpQ2[3]*tmpFx[14] + tmpQ2[4]*tmpFx[18]; -tmpQ1[3] = + tmpQ2[0]*tmpFx[3] + tmpQ2[1]*tmpFx[7] + tmpQ2[2]*tmpFx[11] + tmpQ2[3]*tmpFx[15] + tmpQ2[4]*tmpFx[19]; -tmpQ1[4] = + tmpQ2[5]*tmpFx[0] + tmpQ2[6]*tmpFx[4] + tmpQ2[7]*tmpFx[8] + tmpQ2[8]*tmpFx[12] + tmpQ2[9]*tmpFx[16]; -tmpQ1[5] = + tmpQ2[5]*tmpFx[1] + tmpQ2[6]*tmpFx[5] + tmpQ2[7]*tmpFx[9] + tmpQ2[8]*tmpFx[13] + tmpQ2[9]*tmpFx[17]; -tmpQ1[6] = + tmpQ2[5]*tmpFx[2] + tmpQ2[6]*tmpFx[6] + tmpQ2[7]*tmpFx[10] + tmpQ2[8]*tmpFx[14] + tmpQ2[9]*tmpFx[18]; -tmpQ1[7] = + tmpQ2[5]*tmpFx[3] + tmpQ2[6]*tmpFx[7] + tmpQ2[7]*tmpFx[11] + tmpQ2[8]*tmpFx[15] + tmpQ2[9]*tmpFx[19]; -tmpQ1[8] = + tmpQ2[10]*tmpFx[0] + tmpQ2[11]*tmpFx[4] + tmpQ2[12]*tmpFx[8] + tmpQ2[13]*tmpFx[12] + tmpQ2[14]*tmpFx[16]; -tmpQ1[9] = + tmpQ2[10]*tmpFx[1] + tmpQ2[11]*tmpFx[5] + tmpQ2[12]*tmpFx[9] + tmpQ2[13]*tmpFx[13] + tmpQ2[14]*tmpFx[17]; -tmpQ1[10] = + tmpQ2[10]*tmpFx[2] + tmpQ2[11]*tmpFx[6] + tmpQ2[12]*tmpFx[10] + tmpQ2[13]*tmpFx[14] + tmpQ2[14]*tmpFx[18]; -tmpQ1[11] = + tmpQ2[10]*tmpFx[3] + tmpQ2[11]*tmpFx[7] + tmpQ2[12]*tmpFx[11] + tmpQ2[13]*tmpFx[15] + tmpQ2[14]*tmpFx[19]; -tmpQ1[12] = + tmpQ2[15]*tmpFx[0] + tmpQ2[16]*tmpFx[4] + tmpQ2[17]*tmpFx[8] + tmpQ2[18]*tmpFx[12] + tmpQ2[19]*tmpFx[16]; -tmpQ1[13] = + tmpQ2[15]*tmpFx[1] + tmpQ2[16]*tmpFx[5] + tmpQ2[17]*tmpFx[9] + tmpQ2[18]*tmpFx[13] + tmpQ2[19]*tmpFx[17]; -tmpQ1[14] = + tmpQ2[15]*tmpFx[2] + tmpQ2[16]*tmpFx[6] + tmpQ2[17]*tmpFx[10] + tmpQ2[18]*tmpFx[14] + tmpQ2[19]*tmpFx[18]; -tmpQ1[15] = + tmpQ2[15]*tmpFx[3] + tmpQ2[16]*tmpFx[7] + tmpQ2[17]*tmpFx[11] + tmpQ2[18]*tmpFx[15] + tmpQ2[19]*tmpFx[19]; -} - -void acado_setObjR1R2( real_t* const tmpFu, real_t* const tmpObjS, real_t* const tmpR1, real_t* const tmpR2 ) -{ -tmpR2[0] = + tmpFu[0]*tmpObjS[0] + tmpFu[1]*tmpObjS[5] + tmpFu[2]*tmpObjS[10] + tmpFu[3]*tmpObjS[15] + tmpFu[4]*tmpObjS[20]; -tmpR2[1] = + tmpFu[0]*tmpObjS[1] + tmpFu[1]*tmpObjS[6] + tmpFu[2]*tmpObjS[11] + tmpFu[3]*tmpObjS[16] + tmpFu[4]*tmpObjS[21]; -tmpR2[2] = + tmpFu[0]*tmpObjS[2] + tmpFu[1]*tmpObjS[7] + tmpFu[2]*tmpObjS[12] + tmpFu[3]*tmpObjS[17] + tmpFu[4]*tmpObjS[22]; -tmpR2[3] = + tmpFu[0]*tmpObjS[3] + tmpFu[1]*tmpObjS[8] + tmpFu[2]*tmpObjS[13] + tmpFu[3]*tmpObjS[18] + tmpFu[4]*tmpObjS[23]; -tmpR2[4] = + tmpFu[0]*tmpObjS[4] + tmpFu[1]*tmpObjS[9] + tmpFu[2]*tmpObjS[14] + tmpFu[3]*tmpObjS[19] + tmpFu[4]*tmpObjS[24]; -tmpR1[0] = + tmpR2[0]*tmpFu[0] + tmpR2[1]*tmpFu[1] + tmpR2[2]*tmpFu[2] + tmpR2[3]*tmpFu[3] + tmpR2[4]*tmpFu[4]; -} - -void acado_setObjQN1QN2( real_t* const tmpFx, real_t* const tmpObjSEndTerm, real_t* const tmpQN1, real_t* const tmpQN2 ) -{ -tmpQN2[0] = + tmpFx[0]*tmpObjSEndTerm[0] + tmpFx[4]*tmpObjSEndTerm[4] + tmpFx[8]*tmpObjSEndTerm[8] + tmpFx[12]*tmpObjSEndTerm[12]; -tmpQN2[1] = + tmpFx[0]*tmpObjSEndTerm[1] + tmpFx[4]*tmpObjSEndTerm[5] + tmpFx[8]*tmpObjSEndTerm[9] + tmpFx[12]*tmpObjSEndTerm[13]; -tmpQN2[2] = + tmpFx[0]*tmpObjSEndTerm[2] + tmpFx[4]*tmpObjSEndTerm[6] + tmpFx[8]*tmpObjSEndTerm[10] + tmpFx[12]*tmpObjSEndTerm[14]; -tmpQN2[3] = + tmpFx[0]*tmpObjSEndTerm[3] + tmpFx[4]*tmpObjSEndTerm[7] + tmpFx[8]*tmpObjSEndTerm[11] + tmpFx[12]*tmpObjSEndTerm[15]; -tmpQN2[4] = + tmpFx[1]*tmpObjSEndTerm[0] + tmpFx[5]*tmpObjSEndTerm[4] + tmpFx[9]*tmpObjSEndTerm[8] + tmpFx[13]*tmpObjSEndTerm[12]; -tmpQN2[5] = + tmpFx[1]*tmpObjSEndTerm[1] + tmpFx[5]*tmpObjSEndTerm[5] + tmpFx[9]*tmpObjSEndTerm[9] + tmpFx[13]*tmpObjSEndTerm[13]; -tmpQN2[6] = + tmpFx[1]*tmpObjSEndTerm[2] + tmpFx[5]*tmpObjSEndTerm[6] + tmpFx[9]*tmpObjSEndTerm[10] + tmpFx[13]*tmpObjSEndTerm[14]; -tmpQN2[7] = + tmpFx[1]*tmpObjSEndTerm[3] + tmpFx[5]*tmpObjSEndTerm[7] + tmpFx[9]*tmpObjSEndTerm[11] + tmpFx[13]*tmpObjSEndTerm[15]; -tmpQN2[8] = + tmpFx[2]*tmpObjSEndTerm[0] + tmpFx[6]*tmpObjSEndTerm[4] + tmpFx[10]*tmpObjSEndTerm[8] + tmpFx[14]*tmpObjSEndTerm[12]; -tmpQN2[9] = + tmpFx[2]*tmpObjSEndTerm[1] + tmpFx[6]*tmpObjSEndTerm[5] + tmpFx[10]*tmpObjSEndTerm[9] + tmpFx[14]*tmpObjSEndTerm[13]; -tmpQN2[10] = + tmpFx[2]*tmpObjSEndTerm[2] + tmpFx[6]*tmpObjSEndTerm[6] + tmpFx[10]*tmpObjSEndTerm[10] + tmpFx[14]*tmpObjSEndTerm[14]; -tmpQN2[11] = + tmpFx[2]*tmpObjSEndTerm[3] + tmpFx[6]*tmpObjSEndTerm[7] + tmpFx[10]*tmpObjSEndTerm[11] + tmpFx[14]*tmpObjSEndTerm[15]; -tmpQN2[12] = + tmpFx[3]*tmpObjSEndTerm[0] + tmpFx[7]*tmpObjSEndTerm[4] + tmpFx[11]*tmpObjSEndTerm[8] + tmpFx[15]*tmpObjSEndTerm[12]; -tmpQN2[13] = + tmpFx[3]*tmpObjSEndTerm[1] + tmpFx[7]*tmpObjSEndTerm[5] + tmpFx[11]*tmpObjSEndTerm[9] + tmpFx[15]*tmpObjSEndTerm[13]; -tmpQN2[14] = + tmpFx[3]*tmpObjSEndTerm[2] + tmpFx[7]*tmpObjSEndTerm[6] + tmpFx[11]*tmpObjSEndTerm[10] + tmpFx[15]*tmpObjSEndTerm[14]; -tmpQN2[15] = + tmpFx[3]*tmpObjSEndTerm[3] + tmpFx[7]*tmpObjSEndTerm[7] + tmpFx[11]*tmpObjSEndTerm[11] + tmpFx[15]*tmpObjSEndTerm[15]; -tmpQN1[0] = + tmpQN2[0]*tmpFx[0] + tmpQN2[1]*tmpFx[4] + tmpQN2[2]*tmpFx[8] + tmpQN2[3]*tmpFx[12]; -tmpQN1[1] = + tmpQN2[0]*tmpFx[1] + tmpQN2[1]*tmpFx[5] + tmpQN2[2]*tmpFx[9] + tmpQN2[3]*tmpFx[13]; -tmpQN1[2] = + tmpQN2[0]*tmpFx[2] + tmpQN2[1]*tmpFx[6] + tmpQN2[2]*tmpFx[10] + tmpQN2[3]*tmpFx[14]; -tmpQN1[3] = + tmpQN2[0]*tmpFx[3] + tmpQN2[1]*tmpFx[7] + tmpQN2[2]*tmpFx[11] + tmpQN2[3]*tmpFx[15]; -tmpQN1[4] = + tmpQN2[4]*tmpFx[0] + tmpQN2[5]*tmpFx[4] + tmpQN2[6]*tmpFx[8] + tmpQN2[7]*tmpFx[12]; -tmpQN1[5] = + tmpQN2[4]*tmpFx[1] + tmpQN2[5]*tmpFx[5] + tmpQN2[6]*tmpFx[9] + tmpQN2[7]*tmpFx[13]; -tmpQN1[6] = + tmpQN2[4]*tmpFx[2] + tmpQN2[5]*tmpFx[6] + tmpQN2[6]*tmpFx[10] + tmpQN2[7]*tmpFx[14]; -tmpQN1[7] = + tmpQN2[4]*tmpFx[3] + tmpQN2[5]*tmpFx[7] + tmpQN2[6]*tmpFx[11] + tmpQN2[7]*tmpFx[15]; -tmpQN1[8] = + tmpQN2[8]*tmpFx[0] + tmpQN2[9]*tmpFx[4] + tmpQN2[10]*tmpFx[8] + tmpQN2[11]*tmpFx[12]; -tmpQN1[9] = + tmpQN2[8]*tmpFx[1] + tmpQN2[9]*tmpFx[5] + tmpQN2[10]*tmpFx[9] + tmpQN2[11]*tmpFx[13]; -tmpQN1[10] = + tmpQN2[8]*tmpFx[2] + tmpQN2[9]*tmpFx[6] + tmpQN2[10]*tmpFx[10] + tmpQN2[11]*tmpFx[14]; -tmpQN1[11] = + tmpQN2[8]*tmpFx[3] + tmpQN2[9]*tmpFx[7] + tmpQN2[10]*tmpFx[11] + tmpQN2[11]*tmpFx[15]; -tmpQN1[12] = + tmpQN2[12]*tmpFx[0] + tmpQN2[13]*tmpFx[4] + tmpQN2[14]*tmpFx[8] + tmpQN2[15]*tmpFx[12]; -tmpQN1[13] = + tmpQN2[12]*tmpFx[1] + tmpQN2[13]*tmpFx[5] + tmpQN2[14]*tmpFx[9] + tmpQN2[15]*tmpFx[13]; -tmpQN1[14] = + tmpQN2[12]*tmpFx[2] + tmpQN2[13]*tmpFx[6] + tmpQN2[14]*tmpFx[10] + tmpQN2[15]*tmpFx[14]; -tmpQN1[15] = + tmpQN2[12]*tmpFx[3] + tmpQN2[13]*tmpFx[7] + tmpQN2[14]*tmpFx[11] + tmpQN2[15]*tmpFx[15]; -} - -void acado_evaluateObjective( ) -{ -int runObj; -for (runObj = 0; runObj < 20; ++runObj) -{ -acadoWorkspace.objValueIn[0] = acadoVariables.x[runObj * 4]; -acadoWorkspace.objValueIn[1] = acadoVariables.x[runObj * 4 + 1]; -acadoWorkspace.objValueIn[2] = acadoVariables.x[runObj * 4 + 2]; -acadoWorkspace.objValueIn[3] = acadoVariables.x[runObj * 4 + 3]; -acadoWorkspace.objValueIn[4] = acadoVariables.u[runObj]; -acadoWorkspace.objValueIn[5] = acadoVariables.od[runObj * 12]; -acadoWorkspace.objValueIn[6] = acadoVariables.od[runObj * 12 + 1]; -acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj * 12 + 2]; -acadoWorkspace.objValueIn[8] = acadoVariables.od[runObj * 12 + 3]; -acadoWorkspace.objValueIn[9] = acadoVariables.od[runObj * 12 + 4]; -acadoWorkspace.objValueIn[10] = acadoVariables.od[runObj * 12 + 5]; -acadoWorkspace.objValueIn[11] = acadoVariables.od[runObj * 12 + 6]; -acadoWorkspace.objValueIn[12] = acadoVariables.od[runObj * 12 + 7]; -acadoWorkspace.objValueIn[13] = acadoVariables.od[runObj * 12 + 8]; -acadoWorkspace.objValueIn[14] = acadoVariables.od[runObj * 12 + 9]; -acadoWorkspace.objValueIn[15] = acadoVariables.od[runObj * 12 + 10]; -acadoWorkspace.objValueIn[16] = acadoVariables.od[runObj * 12 + 11]; - -acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); -acadoWorkspace.Dy[runObj * 5] = acadoWorkspace.objValueOut[0]; -acadoWorkspace.Dy[runObj * 5 + 1] = acadoWorkspace.objValueOut[1]; -acadoWorkspace.Dy[runObj * 5 + 2] = acadoWorkspace.objValueOut[2]; -acadoWorkspace.Dy[runObj * 5 + 3] = acadoWorkspace.objValueOut[3]; -acadoWorkspace.Dy[runObj * 5 + 4] = acadoWorkspace.objValueOut[4]; - -acado_setObjQ1Q2( &(acadoWorkspace.objValueOut[ 5 ]), &(acadoVariables.W[ runObj * 25 ]), &(acadoWorkspace.Q1[ runObj * 16 ]), &(acadoWorkspace.Q2[ runObj * 20 ]) ); - -acado_setObjR1R2( &(acadoWorkspace.objValueOut[ 25 ]), &(acadoVariables.W[ runObj * 25 ]), &(acadoWorkspace.R1[ runObj ]), &(acadoWorkspace.R2[ runObj * 5 ]) ); - -} -acadoWorkspace.objValueIn[0] = acadoVariables.x[80]; -acadoWorkspace.objValueIn[1] = acadoVariables.x[81]; -acadoWorkspace.objValueIn[2] = acadoVariables.x[82]; -acadoWorkspace.objValueIn[3] = acadoVariables.x[83]; -acadoWorkspace.objValueIn[4] = acadoVariables.od[240]; -acadoWorkspace.objValueIn[5] = acadoVariables.od[241]; -acadoWorkspace.objValueIn[6] = acadoVariables.od[242]; -acadoWorkspace.objValueIn[7] = acadoVariables.od[243]; -acadoWorkspace.objValueIn[8] = acadoVariables.od[244]; -acadoWorkspace.objValueIn[9] = acadoVariables.od[245]; -acadoWorkspace.objValueIn[10] = acadoVariables.od[246]; -acadoWorkspace.objValueIn[11] = acadoVariables.od[247]; -acadoWorkspace.objValueIn[12] = acadoVariables.od[248]; -acadoWorkspace.objValueIn[13] = acadoVariables.od[249]; -acadoWorkspace.objValueIn[14] = acadoVariables.od[250]; -acadoWorkspace.objValueIn[15] = acadoVariables.od[251]; -acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); - -acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0]; -acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1]; -acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2]; -acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3]; - -acado_setObjQN1QN2( &(acadoWorkspace.objValueOut[ 4 ]), acadoVariables.WN, acadoWorkspace.QN1, acadoWorkspace.QN2 ); - -} - -void acado_multGxd( real_t* const dOld, real_t* const Gx1, real_t* const dNew ) -{ -dNew[0] += + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; -dNew[1] += + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; -dNew[2] += + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; -dNew[3] += + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; -} - -void acado_moveGxT( real_t* const Gx1, real_t* const Gx2 ) -{ -Gx2[0] = Gx1[0]; -Gx2[1] = Gx1[1]; -Gx2[2] = Gx1[2]; -Gx2[3] = Gx1[3]; -Gx2[4] = Gx1[4]; -Gx2[5] = Gx1[5]; -Gx2[6] = Gx1[6]; -Gx2[7] = Gx1[7]; -Gx2[8] = Gx1[8]; -Gx2[9] = Gx1[9]; -Gx2[10] = Gx1[10]; -Gx2[11] = Gx1[11]; -Gx2[12] = Gx1[12]; -Gx2[13] = Gx1[13]; -Gx2[14] = Gx1[14]; -Gx2[15] = Gx1[15]; -} - -void acado_multGxGx( real_t* const Gx1, real_t* const Gx2, real_t* const Gx3 ) -{ -Gx3[0] = + Gx1[0]*Gx2[0] + Gx1[1]*Gx2[4] + Gx1[2]*Gx2[8] + Gx1[3]*Gx2[12]; -Gx3[1] = + Gx1[0]*Gx2[1] + Gx1[1]*Gx2[5] + Gx1[2]*Gx2[9] + Gx1[3]*Gx2[13]; -Gx3[2] = + Gx1[0]*Gx2[2] + Gx1[1]*Gx2[6] + Gx1[2]*Gx2[10] + Gx1[3]*Gx2[14]; -Gx3[3] = + Gx1[0]*Gx2[3] + Gx1[1]*Gx2[7] + Gx1[2]*Gx2[11] + Gx1[3]*Gx2[15]; -Gx3[4] = + Gx1[4]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[6]*Gx2[8] + Gx1[7]*Gx2[12]; -Gx3[5] = + Gx1[4]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[6]*Gx2[9] + Gx1[7]*Gx2[13]; -Gx3[6] = + Gx1[4]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[6]*Gx2[10] + Gx1[7]*Gx2[14]; -Gx3[7] = + Gx1[4]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[6]*Gx2[11] + Gx1[7]*Gx2[15]; -Gx3[8] = + Gx1[8]*Gx2[0] + Gx1[9]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[11]*Gx2[12]; -Gx3[9] = + Gx1[8]*Gx2[1] + Gx1[9]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[11]*Gx2[13]; -Gx3[10] = + Gx1[8]*Gx2[2] + Gx1[9]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[11]*Gx2[14]; -Gx3[11] = + Gx1[8]*Gx2[3] + Gx1[9]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[11]*Gx2[15]; -Gx3[12] = + Gx1[12]*Gx2[0] + Gx1[13]*Gx2[4] + Gx1[14]*Gx2[8] + Gx1[15]*Gx2[12]; -Gx3[13] = + Gx1[12]*Gx2[1] + Gx1[13]*Gx2[5] + Gx1[14]*Gx2[9] + Gx1[15]*Gx2[13]; -Gx3[14] = + Gx1[12]*Gx2[2] + Gx1[13]*Gx2[6] + Gx1[14]*Gx2[10] + Gx1[15]*Gx2[14]; -Gx3[15] = + Gx1[12]*Gx2[3] + Gx1[13]*Gx2[7] + Gx1[14]*Gx2[11] + Gx1[15]*Gx2[15]; -} - -void acado_multGxGu( real_t* const Gx1, real_t* const Gu1, real_t* const Gu2 ) -{ -Gu2[0] = + Gx1[0]*Gu1[0] + Gx1[1]*Gu1[1] + Gx1[2]*Gu1[2] + Gx1[3]*Gu1[3]; -Gu2[1] = + Gx1[4]*Gu1[0] + Gx1[5]*Gu1[1] + Gx1[6]*Gu1[2] + Gx1[7]*Gu1[3]; -Gu2[2] = + Gx1[8]*Gu1[0] + Gx1[9]*Gu1[1] + Gx1[10]*Gu1[2] + Gx1[11]*Gu1[3]; -Gu2[3] = + Gx1[12]*Gu1[0] + Gx1[13]*Gu1[1] + Gx1[14]*Gu1[2] + Gx1[15]*Gu1[3]; -} - -void acado_moveGuE( real_t* const Gu1, real_t* const Gu2 ) -{ -Gu2[0] = Gu1[0]; -Gu2[1] = Gu1[1]; -Gu2[2] = Gu1[2]; -Gu2[3] = Gu1[3]; -} - -void acado_setBlockH11( int iRow, int iCol, real_t* const Gu1, real_t* const Gu2 ) -{ -acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] += + Gu1[0]*Gu2[0] + Gu1[1]*Gu2[1] + Gu1[2]*Gu2[2] + Gu1[3]*Gu2[3]; -} - -void acado_setBlockH11_R1( int iRow, int iCol, real_t* const R11 ) -{ -acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] = R11[0]; -} - -void acado_zeroBlockH11( int iRow, int iCol ) -{ -acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] = 0.0000000000000000e+00; -} - -void acado_copyHTH( int iRow, int iCol ) -{ -acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] = acadoWorkspace.H[(iCol * 24 + 96) + (iRow + 4)]; -} - -void acado_multQ1d( real_t* const Gx1, real_t* const dOld, real_t* const dNew ) -{ -dNew[0] = + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; -dNew[1] = + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; -dNew[2] = + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; -dNew[3] = + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; -} - -void acado_multQN1d( real_t* const QN1, real_t* const dOld, real_t* const dNew ) -{ -dNew[0] = + acadoWorkspace.QN1[0]*dOld[0] + acadoWorkspace.QN1[1]*dOld[1] + acadoWorkspace.QN1[2]*dOld[2] + acadoWorkspace.QN1[3]*dOld[3]; -dNew[1] = + acadoWorkspace.QN1[4]*dOld[0] + acadoWorkspace.QN1[5]*dOld[1] + acadoWorkspace.QN1[6]*dOld[2] + acadoWorkspace.QN1[7]*dOld[3]; -dNew[2] = + acadoWorkspace.QN1[8]*dOld[0] + acadoWorkspace.QN1[9]*dOld[1] + acadoWorkspace.QN1[10]*dOld[2] + acadoWorkspace.QN1[11]*dOld[3]; -dNew[3] = + acadoWorkspace.QN1[12]*dOld[0] + acadoWorkspace.QN1[13]*dOld[1] + acadoWorkspace.QN1[14]*dOld[2] + acadoWorkspace.QN1[15]*dOld[3]; -} - -void acado_multRDy( real_t* const R2, real_t* const Dy1, real_t* const RDy1 ) -{ -RDy1[0] = + R2[0]*Dy1[0] + R2[1]*Dy1[1] + R2[2]*Dy1[2] + R2[3]*Dy1[3] + R2[4]*Dy1[4]; -} - -void acado_multQDy( real_t* const Q2, real_t* const Dy1, real_t* const QDy1 ) -{ -QDy1[0] = + Q2[0]*Dy1[0] + Q2[1]*Dy1[1] + Q2[2]*Dy1[2] + Q2[3]*Dy1[3] + Q2[4]*Dy1[4]; -QDy1[1] = + Q2[5]*Dy1[0] + Q2[6]*Dy1[1] + Q2[7]*Dy1[2] + Q2[8]*Dy1[3] + Q2[9]*Dy1[4]; -QDy1[2] = + Q2[10]*Dy1[0] + Q2[11]*Dy1[1] + Q2[12]*Dy1[2] + Q2[13]*Dy1[3] + Q2[14]*Dy1[4]; -QDy1[3] = + Q2[15]*Dy1[0] + Q2[16]*Dy1[1] + Q2[17]*Dy1[2] + Q2[18]*Dy1[3] + Q2[19]*Dy1[4]; -} - -void acado_multEQDy( real_t* const E1, real_t* const QDy1, real_t* const U1 ) -{ -U1[0] += + E1[0]*QDy1[0] + E1[1]*QDy1[1] + E1[2]*QDy1[2] + E1[3]*QDy1[3]; -} - -void acado_multQETGx( real_t* const E1, real_t* const Gx1, real_t* const H101 ) -{ -H101[0] += + E1[0]*Gx1[0] + E1[1]*Gx1[4] + E1[2]*Gx1[8] + E1[3]*Gx1[12]; -H101[1] += + E1[0]*Gx1[1] + E1[1]*Gx1[5] + E1[2]*Gx1[9] + E1[3]*Gx1[13]; -H101[2] += + E1[0]*Gx1[2] + E1[1]*Gx1[6] + E1[2]*Gx1[10] + E1[3]*Gx1[14]; -H101[3] += + E1[0]*Gx1[3] + E1[1]*Gx1[7] + E1[2]*Gx1[11] + E1[3]*Gx1[15]; -} - -void acado_zeroBlockH10( real_t* const H101 ) -{ -{ int lCopy; for (lCopy = 0; lCopy < 4; lCopy++) H101[ lCopy ] = 0; } -} - -void acado_multEDu( real_t* const E1, real_t* const U1, real_t* const dNew ) -{ -dNew[0] += + E1[0]*U1[0]; -dNew[1] += + E1[1]*U1[0]; -dNew[2] += + E1[2]*U1[0]; -dNew[3] += + E1[3]*U1[0]; -} - -void acado_zeroBlockH00( ) -{ -acadoWorkspace.H[0] = 0.0000000000000000e+00; -acadoWorkspace.H[1] = 0.0000000000000000e+00; -acadoWorkspace.H[2] = 0.0000000000000000e+00; -acadoWorkspace.H[3] = 0.0000000000000000e+00; -acadoWorkspace.H[24] = 0.0000000000000000e+00; -acadoWorkspace.H[25] = 0.0000000000000000e+00; -acadoWorkspace.H[26] = 0.0000000000000000e+00; -acadoWorkspace.H[27] = 0.0000000000000000e+00; -acadoWorkspace.H[48] = 0.0000000000000000e+00; -acadoWorkspace.H[49] = 0.0000000000000000e+00; -acadoWorkspace.H[50] = 0.0000000000000000e+00; -acadoWorkspace.H[51] = 0.0000000000000000e+00; -acadoWorkspace.H[72] = 0.0000000000000000e+00; -acadoWorkspace.H[73] = 0.0000000000000000e+00; -acadoWorkspace.H[74] = 0.0000000000000000e+00; -acadoWorkspace.H[75] = 0.0000000000000000e+00; -} - -void acado_multCTQC( real_t* const Gx1, real_t* const Gx2 ) -{ -acadoWorkspace.H[0] += + Gx1[0]*Gx2[0] + Gx1[4]*Gx2[4] + Gx1[8]*Gx2[8] + Gx1[12]*Gx2[12]; -acadoWorkspace.H[1] += + Gx1[0]*Gx2[1] + Gx1[4]*Gx2[5] + Gx1[8]*Gx2[9] + Gx1[12]*Gx2[13]; -acadoWorkspace.H[2] += + Gx1[0]*Gx2[2] + Gx1[4]*Gx2[6] + Gx1[8]*Gx2[10] + Gx1[12]*Gx2[14]; -acadoWorkspace.H[3] += + Gx1[0]*Gx2[3] + Gx1[4]*Gx2[7] + Gx1[8]*Gx2[11] + Gx1[12]*Gx2[15]; -acadoWorkspace.H[24] += + Gx1[1]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[9]*Gx2[8] + Gx1[13]*Gx2[12]; -acadoWorkspace.H[25] += + Gx1[1]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[9]*Gx2[9] + Gx1[13]*Gx2[13]; -acadoWorkspace.H[26] += + Gx1[1]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[9]*Gx2[10] + Gx1[13]*Gx2[14]; -acadoWorkspace.H[27] += + Gx1[1]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[9]*Gx2[11] + Gx1[13]*Gx2[15]; -acadoWorkspace.H[48] += + Gx1[2]*Gx2[0] + Gx1[6]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[14]*Gx2[12]; -acadoWorkspace.H[49] += + Gx1[2]*Gx2[1] + Gx1[6]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[14]*Gx2[13]; -acadoWorkspace.H[50] += + Gx1[2]*Gx2[2] + Gx1[6]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[14]*Gx2[14]; -acadoWorkspace.H[51] += + Gx1[2]*Gx2[3] + Gx1[6]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[14]*Gx2[15]; -acadoWorkspace.H[72] += + Gx1[3]*Gx2[0] + Gx1[7]*Gx2[4] + Gx1[11]*Gx2[8] + Gx1[15]*Gx2[12]; -acadoWorkspace.H[73] += + Gx1[3]*Gx2[1] + Gx1[7]*Gx2[5] + Gx1[11]*Gx2[9] + Gx1[15]*Gx2[13]; -acadoWorkspace.H[74] += + Gx1[3]*Gx2[2] + Gx1[7]*Gx2[6] + Gx1[11]*Gx2[10] + Gx1[15]*Gx2[14]; -acadoWorkspace.H[75] += + Gx1[3]*Gx2[3] + Gx1[7]*Gx2[7] + Gx1[11]*Gx2[11] + Gx1[15]*Gx2[15]; -} - -void acado_macCTSlx( real_t* const C0, real_t* const g0 ) -{ -g0[0] += 0.0; -; -g0[1] += 0.0; -; -g0[2] += 0.0; -; -g0[3] += 0.0; -; -} - -void acado_macETSlu( real_t* const E0, real_t* const g1 ) -{ -g1[0] += 0.0; -; -} - -void acado_condensePrep( ) -{ -acado_moveGuE( acadoWorkspace.evGu, acadoWorkspace.E ); -acado_moveGxT( &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.T ); -acado_multGxd( acadoWorkspace.d, &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.d[ 4 ]) ); -acado_multGxGx( acadoWorkspace.T, acadoWorkspace.evGx, &(acadoWorkspace.evGx[ 16 ]) ); - -acado_multGxGu( acadoWorkspace.T, acadoWorkspace.E, &(acadoWorkspace.E[ 4 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 4 ]), &(acadoWorkspace.E[ 8 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 4 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.d[ 8 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.evGx[ 32 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.E[ 12 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.E[ 16 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 8 ]), &(acadoWorkspace.E[ 20 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 8 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.d[ 12 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.evGx[ 48 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.E[ 24 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.E[ 28 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.E[ 32 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 12 ]), &(acadoWorkspace.E[ 36 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.d[ 16 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.evGx[ 64 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.E[ 40 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.E[ 44 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.E[ 48 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.E[ 52 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 16 ]), &(acadoWorkspace.E[ 56 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 16 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.d[ 20 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.evGx[ 80 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.E[ 60 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.E[ 64 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.E[ 68 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.E[ 72 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.E[ 76 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 20 ]), &(acadoWorkspace.E[ 80 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 20 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.d[ 24 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.evGx[ 96 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.E[ 84 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.E[ 88 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.E[ 92 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.E[ 96 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.E[ 100 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.E[ 104 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 24 ]), &(acadoWorkspace.E[ 108 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.d[ 28 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.evGx[ 112 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.E[ 112 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.E[ 116 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.E[ 120 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.E[ 124 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.E[ 128 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.E[ 132 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.E[ 136 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 28 ]), &(acadoWorkspace.E[ 140 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 28 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.d[ 32 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.evGx[ 128 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.E[ 144 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.E[ 148 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.E[ 152 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.E[ 156 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.E[ 160 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.E[ 164 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.E[ 168 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.E[ 172 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 32 ]), &(acadoWorkspace.E[ 176 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 32 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.d[ 36 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.evGx[ 144 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.E[ 180 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.E[ 184 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.E[ 188 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.E[ 192 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.E[ 196 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.E[ 200 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.E[ 204 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.E[ 208 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.E[ 212 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 36 ]), &(acadoWorkspace.E[ 216 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.d[ 40 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.evGx[ 160 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.E[ 220 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.E[ 224 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.E[ 228 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.E[ 232 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.E[ 236 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.E[ 240 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.E[ 244 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.E[ 248 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.E[ 252 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.E[ 256 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 40 ]), &(acadoWorkspace.E[ 260 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 40 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.d[ 44 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.evGx[ 176 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.E[ 264 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.E[ 268 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.E[ 272 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.E[ 276 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.E[ 280 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.E[ 284 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.E[ 288 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.E[ 292 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.E[ 296 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.E[ 300 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.E[ 304 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 44 ]), &(acadoWorkspace.E[ 308 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 44 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.d[ 48 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.evGx[ 192 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.E[ 312 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.E[ 316 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.E[ 320 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.E[ 324 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.E[ 328 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.E[ 332 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.E[ 336 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.E[ 340 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.E[ 344 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.E[ 348 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.E[ 352 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.E[ 356 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 48 ]), &(acadoWorkspace.E[ 360 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.d[ 52 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.evGx[ 208 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.E[ 364 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.E[ 368 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.E[ 372 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.E[ 376 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.E[ 380 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.E[ 384 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.E[ 388 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.E[ 392 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.E[ 396 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.E[ 400 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.E[ 404 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.E[ 408 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.E[ 412 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 52 ]), &(acadoWorkspace.E[ 416 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 52 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.d[ 56 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.evGx[ 224 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.E[ 420 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.E[ 424 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.E[ 428 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.E[ 432 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.E[ 436 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.E[ 440 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.E[ 444 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.E[ 448 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.E[ 452 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.E[ 456 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.E[ 460 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.E[ 464 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.E[ 468 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.E[ 472 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 56 ]), &(acadoWorkspace.E[ 476 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 56 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.d[ 60 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.evGx[ 240 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.E[ 480 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.E[ 484 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.E[ 488 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.E[ 492 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.E[ 496 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.E[ 500 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.E[ 504 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.E[ 508 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.E[ 512 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.E[ 516 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.E[ 520 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.E[ 524 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.E[ 528 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.E[ 532 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.E[ 536 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 60 ]), &(acadoWorkspace.E[ 540 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.d[ 64 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.evGx[ 256 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.E[ 544 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.E[ 548 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.E[ 552 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.E[ 556 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.E[ 560 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.E[ 564 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.E[ 568 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.E[ 572 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.E[ 576 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.E[ 580 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.E[ 584 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.E[ 588 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.E[ 592 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.E[ 596 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.E[ 600 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.E[ 604 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 64 ]), &(acadoWorkspace.E[ 608 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 64 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.d[ 68 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.evGx[ 272 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.E[ 612 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.E[ 616 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.E[ 620 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.E[ 624 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.E[ 628 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.E[ 632 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.E[ 636 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.E[ 640 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.E[ 644 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.E[ 648 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.E[ 652 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.E[ 656 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.E[ 660 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.E[ 664 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.E[ 668 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.E[ 672 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.E[ 676 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 68 ]), &(acadoWorkspace.E[ 680 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 68 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.d[ 72 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.evGx[ 288 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.E[ 684 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.E[ 688 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.E[ 692 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.E[ 696 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.E[ 700 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.E[ 704 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.E[ 708 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.E[ 712 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.E[ 716 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.E[ 720 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.E[ 724 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.E[ 728 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.E[ 732 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.E[ 736 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.E[ 740 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.E[ 744 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.E[ 748 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.E[ 752 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 72 ]), &(acadoWorkspace.E[ 756 ]) ); - -acado_moveGxT( &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.T ); -acado_multGxd( &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.d[ 76 ]) ); -acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.evGx[ 304 ]) ); - -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.E[ 760 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.E[ 764 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.E[ 768 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.E[ 772 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.E[ 776 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.E[ 780 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.E[ 784 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.E[ 788 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.E[ 792 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.E[ 796 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.E[ 800 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.E[ 804 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.E[ 808 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.E[ 812 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.E[ 816 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.E[ 820 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.E[ 824 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.E[ 828 ]) ); -acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.E[ 832 ]) ); - -acado_moveGuE( &(acadoWorkspace.evGu[ 76 ]), &(acadoWorkspace.E[ 836 ]) ); - -acado_multGxGx( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.evGx, acadoWorkspace.QGx ); -acado_multGxGx( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); -acado_multGxGx( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); -acado_multGxGx( acadoWorkspace.QN1, &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); - -acado_multGxGu( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.E, acadoWorkspace.QE ); -acado_multGxGu( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QE[ 4 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.QE[ 8 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 12 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QE[ 16 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.QE[ 20 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 24 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 28 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QE[ 32 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 36 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 40 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 44 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 48 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QE[ 52 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.QE[ 56 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 60 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 64 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 68 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 72 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QE[ 76 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.QE[ 80 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 84 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 88 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 92 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 96 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 100 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QE[ 104 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 112 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 116 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 120 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 124 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 128 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 132 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 144 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 148 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 152 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 156 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 160 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 164 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 180 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 184 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 188 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 192 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 196 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 200 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 220 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 224 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 228 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 232 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 236 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 240 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 264 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 268 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 272 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 276 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 280 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 284 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 312 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 316 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 320 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 324 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 328 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 332 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 364 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 368 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 372 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 376 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 380 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 384 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 420 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 424 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 428 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 432 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 436 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 440 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 480 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 484 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 488 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 492 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 496 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 500 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 544 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 548 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 552 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 556 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 560 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 564 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 612 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 616 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 620 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 624 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 628 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 632 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 684 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 688 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 692 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 696 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 700 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 704 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 760 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 764 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 768 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 772 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 776 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 780 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 784 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 788 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 792 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 796 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 800 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 804 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 808 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 812 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 816 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 820 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 824 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 828 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QE[ 832 ]) ); -acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_zeroBlockH00( ); -acado_multCTQC( acadoWorkspace.evGx, acadoWorkspace.QGx ); -acado_multCTQC( &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); -acado_multCTQC( &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); - -acado_zeroBlockH10( acadoWorkspace.H10 ); -acado_multQETGx( acadoWorkspace.QE, acadoWorkspace.evGx, acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 4 ]), &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 12 ]), &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 24 ]), &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 40 ]), &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 60 ]), &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 84 ]), &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 112 ]), &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 144 ]), &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 180 ]), &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 220 ]), &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 264 ]), &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 312 ]), &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 364 ]), &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 420 ]), &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 480 ]), &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 544 ]), &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 612 ]), &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 684 ]), &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.H10 ); -acado_multQETGx( &(acadoWorkspace.QE[ 760 ]), &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.H10 ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 8 ]), &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 16 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 28 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 44 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 64 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 88 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 116 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 148 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 184 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 224 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 268 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 316 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 368 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 424 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 484 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 548 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 616 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 688 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 764 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 4 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 20 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 32 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 48 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 68 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 92 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 120 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 152 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 188 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 228 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 272 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 320 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 372 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 428 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 488 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 552 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 620 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 692 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 768 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 8 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 36 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 52 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 72 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 96 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 124 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 156 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 192 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 232 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 276 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 324 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 376 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 432 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 492 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 556 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 624 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 696 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 772 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 12 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 56 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 76 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 100 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 128 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 160 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 196 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 236 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 280 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 328 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 380 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 436 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 496 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 560 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 628 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 700 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 776 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 16 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 80 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 104 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 132 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 164 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 200 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 240 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 284 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 332 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 384 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 440 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 500 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 564 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 632 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 704 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 780 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 20 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 108 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 136 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 168 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 204 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 244 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 288 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 336 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 388 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 444 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 504 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 568 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 636 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 708 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 784 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 24 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 140 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 172 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 208 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 248 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 292 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 340 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 392 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 448 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 508 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 572 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 640 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 712 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 788 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 28 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 176 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 212 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 252 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 296 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 344 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 396 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 452 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 512 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 576 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 644 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 716 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 792 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 32 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 216 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 256 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 300 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 348 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 400 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 456 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 516 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 580 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 648 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 720 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 796 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 36 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 260 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 304 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 352 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 404 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 460 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 520 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 584 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 652 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 724 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 800 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 40 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 308 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 356 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 408 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 464 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 524 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 588 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 656 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 728 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 804 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 44 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 360 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 412 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 468 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 528 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 592 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 660 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 732 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 808 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 48 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 52 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 416 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 52 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 472 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 52 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 532 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 52 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 596 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 52 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 664 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 52 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 736 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 52 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 812 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 52 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 56 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 476 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 56 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 536 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 56 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 600 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 56 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 668 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 56 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 740 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 56 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 816 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 56 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 60 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 540 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 60 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 604 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 60 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 672 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 60 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 744 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 60 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 820 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 60 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 64 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 608 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 64 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 676 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 64 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 748 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 64 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 824 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 64 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 68 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 680 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 68 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 752 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 68 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 828 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 68 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 72 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 756 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 72 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 832 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 72 ]) ); -acado_zeroBlockH10( &(acadoWorkspace.H10[ 76 ]) ); -acado_multQETGx( &(acadoWorkspace.QE[ 836 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 76 ]) ); - -acadoWorkspace.H[4] = acadoWorkspace.H10[0]; -acadoWorkspace.H[5] = acadoWorkspace.H10[4]; -acadoWorkspace.H[6] = acadoWorkspace.H10[8]; -acadoWorkspace.H[7] = acadoWorkspace.H10[12]; -acadoWorkspace.H[8] = acadoWorkspace.H10[16]; -acadoWorkspace.H[9] = acadoWorkspace.H10[20]; -acadoWorkspace.H[10] = acadoWorkspace.H10[24]; -acadoWorkspace.H[11] = acadoWorkspace.H10[28]; -acadoWorkspace.H[12] = acadoWorkspace.H10[32]; -acadoWorkspace.H[13] = acadoWorkspace.H10[36]; -acadoWorkspace.H[14] = acadoWorkspace.H10[40]; -acadoWorkspace.H[15] = acadoWorkspace.H10[44]; -acadoWorkspace.H[16] = acadoWorkspace.H10[48]; -acadoWorkspace.H[17] = acadoWorkspace.H10[52]; -acadoWorkspace.H[18] = acadoWorkspace.H10[56]; -acadoWorkspace.H[19] = acadoWorkspace.H10[60]; -acadoWorkspace.H[20] = acadoWorkspace.H10[64]; -acadoWorkspace.H[21] = acadoWorkspace.H10[68]; -acadoWorkspace.H[22] = acadoWorkspace.H10[72]; -acadoWorkspace.H[23] = acadoWorkspace.H10[76]; -acadoWorkspace.H[28] = acadoWorkspace.H10[1]; -acadoWorkspace.H[29] = acadoWorkspace.H10[5]; -acadoWorkspace.H[30] = acadoWorkspace.H10[9]; -acadoWorkspace.H[31] = acadoWorkspace.H10[13]; -acadoWorkspace.H[32] = acadoWorkspace.H10[17]; -acadoWorkspace.H[33] = acadoWorkspace.H10[21]; -acadoWorkspace.H[34] = acadoWorkspace.H10[25]; -acadoWorkspace.H[35] = acadoWorkspace.H10[29]; -acadoWorkspace.H[36] = acadoWorkspace.H10[33]; -acadoWorkspace.H[37] = acadoWorkspace.H10[37]; -acadoWorkspace.H[38] = acadoWorkspace.H10[41]; -acadoWorkspace.H[39] = acadoWorkspace.H10[45]; -acadoWorkspace.H[40] = acadoWorkspace.H10[49]; -acadoWorkspace.H[41] = acadoWorkspace.H10[53]; -acadoWorkspace.H[42] = acadoWorkspace.H10[57]; -acadoWorkspace.H[43] = acadoWorkspace.H10[61]; -acadoWorkspace.H[44] = acadoWorkspace.H10[65]; -acadoWorkspace.H[45] = acadoWorkspace.H10[69]; -acadoWorkspace.H[46] = acadoWorkspace.H10[73]; -acadoWorkspace.H[47] = acadoWorkspace.H10[77]; -acadoWorkspace.H[52] = acadoWorkspace.H10[2]; -acadoWorkspace.H[53] = acadoWorkspace.H10[6]; -acadoWorkspace.H[54] = acadoWorkspace.H10[10]; -acadoWorkspace.H[55] = acadoWorkspace.H10[14]; -acadoWorkspace.H[56] = acadoWorkspace.H10[18]; -acadoWorkspace.H[57] = acadoWorkspace.H10[22]; -acadoWorkspace.H[58] = acadoWorkspace.H10[26]; -acadoWorkspace.H[59] = acadoWorkspace.H10[30]; -acadoWorkspace.H[60] = acadoWorkspace.H10[34]; -acadoWorkspace.H[61] = acadoWorkspace.H10[38]; -acadoWorkspace.H[62] = acadoWorkspace.H10[42]; -acadoWorkspace.H[63] = acadoWorkspace.H10[46]; -acadoWorkspace.H[64] = acadoWorkspace.H10[50]; -acadoWorkspace.H[65] = acadoWorkspace.H10[54]; -acadoWorkspace.H[66] = acadoWorkspace.H10[58]; -acadoWorkspace.H[67] = acadoWorkspace.H10[62]; -acadoWorkspace.H[68] = acadoWorkspace.H10[66]; -acadoWorkspace.H[69] = acadoWorkspace.H10[70]; -acadoWorkspace.H[70] = acadoWorkspace.H10[74]; -acadoWorkspace.H[71] = acadoWorkspace.H10[78]; -acadoWorkspace.H[76] = acadoWorkspace.H10[3]; -acadoWorkspace.H[77] = acadoWorkspace.H10[7]; -acadoWorkspace.H[78] = acadoWorkspace.H10[11]; -acadoWorkspace.H[79] = acadoWorkspace.H10[15]; -acadoWorkspace.H[80] = acadoWorkspace.H10[19]; -acadoWorkspace.H[81] = acadoWorkspace.H10[23]; -acadoWorkspace.H[82] = acadoWorkspace.H10[27]; -acadoWorkspace.H[83] = acadoWorkspace.H10[31]; -acadoWorkspace.H[84] = acadoWorkspace.H10[35]; -acadoWorkspace.H[85] = acadoWorkspace.H10[39]; -acadoWorkspace.H[86] = acadoWorkspace.H10[43]; -acadoWorkspace.H[87] = acadoWorkspace.H10[47]; -acadoWorkspace.H[88] = acadoWorkspace.H10[51]; -acadoWorkspace.H[89] = acadoWorkspace.H10[55]; -acadoWorkspace.H[90] = acadoWorkspace.H10[59]; -acadoWorkspace.H[91] = acadoWorkspace.H10[63]; -acadoWorkspace.H[92] = acadoWorkspace.H10[67]; -acadoWorkspace.H[93] = acadoWorkspace.H10[71]; -acadoWorkspace.H[94] = acadoWorkspace.H10[75]; -acadoWorkspace.H[95] = acadoWorkspace.H10[79]; - -acado_setBlockH11_R1( 0, 0, acadoWorkspace.R1 ); -acado_setBlockH11( 0, 0, acadoWorkspace.E, acadoWorkspace.QE ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QE[ 4 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 12 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 24 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 40 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 60 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 84 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 112 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 144 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 180 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 220 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 264 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 312 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 364 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 420 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 480 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 544 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 612 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 684 ]) ); -acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 760 ]) ); - -acado_zeroBlockH11( 0, 1 ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QE[ 8 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 16 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 28 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 44 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 64 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 88 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 116 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 148 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 184 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 224 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 268 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 316 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 368 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 424 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 484 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 548 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 616 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 688 ]) ); -acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 764 ]) ); - -acado_zeroBlockH11( 0, 2 ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 20 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 32 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 48 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 68 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 92 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 120 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 152 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 188 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 228 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 272 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 320 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 372 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 428 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 488 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 552 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 620 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 692 ]) ); -acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 768 ]) ); - -acado_zeroBlockH11( 0, 3 ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 36 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 52 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 72 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 96 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 124 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 156 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 192 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 232 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 276 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 324 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 376 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 432 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 492 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 556 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 624 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 696 ]) ); -acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 772 ]) ); - -acado_zeroBlockH11( 0, 4 ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 56 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 76 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 100 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 128 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 160 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 196 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 236 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 280 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 328 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 380 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 436 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 496 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 560 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 628 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 700 ]) ); -acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 776 ]) ); - -acado_zeroBlockH11( 0, 5 ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 80 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 104 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 132 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 164 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 200 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 240 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 284 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 332 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 384 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 440 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 500 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 564 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 632 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 704 ]) ); -acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 780 ]) ); - -acado_zeroBlockH11( 0, 6 ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 784 ]) ); - -acado_zeroBlockH11( 0, 7 ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 0, 8 ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 0, 9 ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 0, 10 ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 0, 11 ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 0, 12 ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 0, 13 ); -acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 0, 14 ); -acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 0, 15 ); -acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 0, 16 ); -acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 0, 17 ); -acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 0, 18 ); -acado_setBlockH11( 0, 18, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 0, 18, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 0, 19 ); -acado_setBlockH11( 0, 19, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 1, 1, &(acadoWorkspace.R1[ 1 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.QE[ 8 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QE[ 16 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 28 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 44 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 64 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 88 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 116 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 148 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 184 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 224 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 268 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 316 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 368 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 424 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 484 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 548 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 616 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 688 ]) ); -acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 764 ]) ); - -acado_zeroBlockH11( 1, 2 ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QE[ 20 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 32 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 48 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 68 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 92 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 120 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 152 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 188 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 228 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 272 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 320 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 372 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 428 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 488 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 552 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 620 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 692 ]) ); -acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 768 ]) ); - -acado_zeroBlockH11( 1, 3 ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 36 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 52 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 72 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 96 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 124 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 156 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 192 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 232 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 276 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 324 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 376 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 432 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 492 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 556 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 624 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 696 ]) ); -acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 772 ]) ); - -acado_zeroBlockH11( 1, 4 ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 56 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 76 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 100 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 128 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 160 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 196 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 236 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 280 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 328 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 380 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 436 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 496 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 560 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 628 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 700 ]) ); -acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 776 ]) ); - -acado_zeroBlockH11( 1, 5 ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 80 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 104 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 132 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 164 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 200 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 240 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 284 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 332 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 384 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 440 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 500 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 564 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 632 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 704 ]) ); -acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 780 ]) ); - -acado_zeroBlockH11( 1, 6 ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 784 ]) ); - -acado_zeroBlockH11( 1, 7 ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 1, 8 ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 1, 9 ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 1, 10 ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 1, 11 ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 1, 12 ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 1, 13 ); -acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 1, 14 ); -acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 1, 15 ); -acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 1, 16 ); -acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 1, 17 ); -acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 1, 18 ); -acado_setBlockH11( 1, 18, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 1, 18, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 1, 19 ); -acado_setBlockH11( 1, 19, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 2, 2, &(acadoWorkspace.R1[ 2 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.QE[ 20 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QE[ 32 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 48 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 68 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 92 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 120 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 152 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 188 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 228 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 272 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 320 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 372 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 428 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 488 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 552 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 620 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 692 ]) ); -acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 768 ]) ); - -acado_zeroBlockH11( 2, 3 ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QE[ 36 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 52 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 72 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 96 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 124 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 156 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 192 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 232 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 276 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 324 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 376 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 432 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 492 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 556 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 624 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 696 ]) ); -acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 772 ]) ); - -acado_zeroBlockH11( 2, 4 ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 56 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 76 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 100 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 128 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 160 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 196 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 236 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 280 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 328 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 380 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 436 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 496 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 560 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 628 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 700 ]) ); -acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 776 ]) ); - -acado_zeroBlockH11( 2, 5 ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 80 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 104 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 132 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 164 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 200 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 240 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 284 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 332 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 384 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 440 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 500 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 564 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 632 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 704 ]) ); -acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 780 ]) ); - -acado_zeroBlockH11( 2, 6 ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 784 ]) ); - -acado_zeroBlockH11( 2, 7 ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 2, 8 ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 2, 9 ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 2, 10 ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 2, 11 ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 2, 12 ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 2, 13 ); -acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 2, 14 ); -acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 2, 15 ); -acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 2, 16 ); -acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 2, 17 ); -acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 2, 18 ); -acado_setBlockH11( 2, 18, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 2, 18, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 2, 19 ); -acado_setBlockH11( 2, 19, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 3, 3, &(acadoWorkspace.R1[ 3 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 36 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QE[ 52 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 72 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 96 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 124 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 156 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 192 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 232 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 276 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 324 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 376 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 432 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 492 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 556 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 624 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 696 ]) ); -acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 772 ]) ); - -acado_zeroBlockH11( 3, 4 ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QE[ 56 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 76 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 100 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 128 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 160 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 196 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 236 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 280 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 328 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 380 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 436 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 496 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 560 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 628 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 700 ]) ); -acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 776 ]) ); - -acado_zeroBlockH11( 3, 5 ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 80 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 104 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 132 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 164 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 200 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 240 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 284 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 332 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 384 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 440 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 500 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 564 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 632 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 704 ]) ); -acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 780 ]) ); - -acado_zeroBlockH11( 3, 6 ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 784 ]) ); - -acado_zeroBlockH11( 3, 7 ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 3, 8 ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 3, 9 ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 3, 10 ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 3, 11 ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 3, 12 ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 3, 13 ); -acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 3, 14 ); -acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 3, 15 ); -acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 3, 16 ); -acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 3, 17 ); -acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 3, 18 ); -acado_setBlockH11( 3, 18, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 3, 18, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 3, 19 ); -acado_setBlockH11( 3, 19, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 4, 4, &(acadoWorkspace.R1[ 4 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.QE[ 56 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QE[ 76 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 100 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 128 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 160 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 196 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 236 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 280 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 328 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 380 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 436 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 496 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 560 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 628 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 700 ]) ); -acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 776 ]) ); - -acado_zeroBlockH11( 4, 5 ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QE[ 80 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 104 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 132 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 164 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 200 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 240 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 284 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 332 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 384 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 440 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 500 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 564 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 632 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 704 ]) ); -acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 780 ]) ); - -acado_zeroBlockH11( 4, 6 ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 784 ]) ); - -acado_zeroBlockH11( 4, 7 ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 4, 8 ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 4, 9 ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 4, 10 ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 4, 11 ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 4, 12 ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 4, 13 ); -acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 4, 14 ); -acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 4, 15 ); -acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 4, 16 ); -acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 4, 17 ); -acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 4, 18 ); -acado_setBlockH11( 4, 18, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 4, 18, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 4, 19 ); -acado_setBlockH11( 4, 19, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 5, 5, &(acadoWorkspace.R1[ 5 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.QE[ 80 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QE[ 104 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 132 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 164 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 200 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 240 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 284 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 332 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 384 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 440 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 500 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 564 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 632 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 704 ]) ); -acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 780 ]) ); - -acado_zeroBlockH11( 5, 6 ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 784 ]) ); - -acado_zeroBlockH11( 5, 7 ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 5, 8 ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 5, 9 ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 5, 10 ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 5, 11 ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 5, 12 ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 5, 13 ); -acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 5, 14 ); -acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 5, 15 ); -acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 5, 16 ); -acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 5, 17 ); -acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 5, 18 ); -acado_setBlockH11( 5, 18, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 5, 18, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 5, 19 ); -acado_setBlockH11( 5, 19, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 6, 6, &(acadoWorkspace.R1[ 6 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 108 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QE[ 136 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 168 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 204 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 244 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 288 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 336 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 388 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 444 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 504 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 568 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 636 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 708 ]) ); -acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 784 ]) ); - -acado_zeroBlockH11( 6, 7 ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 6, 8 ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 6, 9 ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 6, 10 ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 6, 11 ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 6, 12 ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 6, 13 ); -acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 6, 14 ); -acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 6, 15 ); -acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 6, 16 ); -acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 6, 17 ); -acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 6, 18 ); -acado_setBlockH11( 6, 18, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 6, 18, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 6, 19 ); -acado_setBlockH11( 6, 19, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 7, 7, &(acadoWorkspace.R1[ 7 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.QE[ 140 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QE[ 172 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 208 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 248 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 292 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 340 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 392 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 448 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 508 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 572 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 640 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 712 ]) ); -acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 788 ]) ); - -acado_zeroBlockH11( 7, 8 ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 7, 9 ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 7, 10 ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 7, 11 ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 7, 12 ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 7, 13 ); -acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 7, 14 ); -acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 7, 15 ); -acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 7, 16 ); -acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 7, 17 ); -acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 7, 18 ); -acado_setBlockH11( 7, 18, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 7, 18, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 7, 19 ); -acado_setBlockH11( 7, 19, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 8, 8, &(acadoWorkspace.R1[ 8 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.QE[ 176 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QE[ 212 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 252 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 296 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 344 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 396 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 452 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 512 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 576 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 644 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 716 ]) ); -acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 792 ]) ); - -acado_zeroBlockH11( 8, 9 ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 8, 10 ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 8, 11 ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 8, 12 ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 8, 13 ); -acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 8, 14 ); -acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 8, 15 ); -acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 8, 16 ); -acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 8, 17 ); -acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 8, 18 ); -acado_setBlockH11( 8, 18, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 8, 18, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 8, 19 ); -acado_setBlockH11( 8, 19, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 9, 9, &(acadoWorkspace.R1[ 9 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 216 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QE[ 256 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 300 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 348 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 400 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 456 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 516 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 580 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 648 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 720 ]) ); -acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 796 ]) ); - -acado_zeroBlockH11( 9, 10 ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 9, 11 ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 9, 12 ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 9, 13 ); -acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 9, 14 ); -acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 9, 15 ); -acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 9, 16 ); -acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 9, 17 ); -acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 9, 18 ); -acado_setBlockH11( 9, 18, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 9, 18, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 9, 19 ); -acado_setBlockH11( 9, 19, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 10, 10, &(acadoWorkspace.R1[ 10 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.QE[ 260 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QE[ 304 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 352 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 404 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 460 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 520 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 584 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 652 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 724 ]) ); -acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 800 ]) ); - -acado_zeroBlockH11( 10, 11 ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 10, 12 ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 10, 13 ); -acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 10, 14 ); -acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 10, 15 ); -acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 10, 16 ); -acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 10, 17 ); -acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 10, 18 ); -acado_setBlockH11( 10, 18, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 10, 18, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 10, 19 ); -acado_setBlockH11( 10, 19, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 11, 11, &(acadoWorkspace.R1[ 11 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.QE[ 308 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QE[ 356 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 408 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 464 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 524 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 588 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 656 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 728 ]) ); -acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 804 ]) ); - -acado_zeroBlockH11( 11, 12 ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 11, 13 ); -acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 11, 14 ); -acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 11, 15 ); -acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 11, 16 ); -acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 11, 17 ); -acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 11, 18 ); -acado_setBlockH11( 11, 18, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 11, 18, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 11, 19 ); -acado_setBlockH11( 11, 19, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 12, 12, &(acadoWorkspace.R1[ 12 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 360 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QE[ 412 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 468 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 528 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 592 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 660 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 732 ]) ); -acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 808 ]) ); - -acado_zeroBlockH11( 12, 13 ); -acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 12, 14 ); -acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 12, 15 ); -acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 12, 16 ); -acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 12, 17 ); -acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 12, 18 ); -acado_setBlockH11( 12, 18, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 12, 18, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 12, 19 ); -acado_setBlockH11( 12, 19, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 13, 13, &(acadoWorkspace.R1[ 13 ]) ); -acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.QE[ 416 ]) ); -acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QE[ 472 ]) ); -acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 532 ]) ); -acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 596 ]) ); -acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 664 ]) ); -acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 736 ]) ); -acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 812 ]) ); - -acado_zeroBlockH11( 13, 14 ); -acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 13, 15 ); -acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 13, 16 ); -acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 13, 17 ); -acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 13, 18 ); -acado_setBlockH11( 13, 18, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 13, 18, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 13, 19 ); -acado_setBlockH11( 13, 19, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 14, 14, &(acadoWorkspace.R1[ 14 ]) ); -acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.QE[ 476 ]) ); -acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QE[ 536 ]) ); -acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 600 ]) ); -acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 668 ]) ); -acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 740 ]) ); -acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 816 ]) ); - -acado_zeroBlockH11( 14, 15 ); -acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 14, 16 ); -acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 14, 17 ); -acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 14, 18 ); -acado_setBlockH11( 14, 18, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 14, 18, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 14, 19 ); -acado_setBlockH11( 14, 19, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 15, 15, &(acadoWorkspace.R1[ 15 ]) ); -acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QE[ 540 ]) ); -acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QE[ 604 ]) ); -acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 672 ]) ); -acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 744 ]) ); -acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 820 ]) ); - -acado_zeroBlockH11( 15, 16 ); -acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 15, 17 ); -acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 15, 18 ); -acado_setBlockH11( 15, 18, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 15, 18, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 15, 19 ); -acado_setBlockH11( 15, 19, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 16, 16, &(acadoWorkspace.R1[ 16 ]) ); -acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.QE[ 608 ]) ); -acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QE[ 676 ]) ); -acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 748 ]) ); -acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 824 ]) ); - -acado_zeroBlockH11( 16, 17 ); -acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 16, 18 ); -acado_setBlockH11( 16, 18, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 16, 18, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 16, 19 ); -acado_setBlockH11( 16, 19, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 17, 17, &(acadoWorkspace.R1[ 17 ]) ); -acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.QE[ 680 ]) ); -acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QE[ 752 ]) ); -acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 828 ]) ); - -acado_zeroBlockH11( 17, 18 ); -acado_setBlockH11( 17, 18, &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 17, 18, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 17, 19 ); -acado_setBlockH11( 17, 19, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 18, 18, &(acadoWorkspace.R1[ 18 ]) ); -acado_setBlockH11( 18, 18, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 756 ]) ); -acado_setBlockH11( 18, 18, &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QE[ 832 ]) ); - -acado_zeroBlockH11( 18, 19 ); -acado_setBlockH11( 18, 19, &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QE[ 836 ]) ); - -acado_setBlockH11_R1( 19, 19, &(acadoWorkspace.R1[ 19 ]) ); -acado_setBlockH11( 19, 19, &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.QE[ 836 ]) ); - - -acado_copyHTH( 1, 0 ); -acado_copyHTH( 2, 0 ); -acado_copyHTH( 2, 1 ); -acado_copyHTH( 3, 0 ); -acado_copyHTH( 3, 1 ); -acado_copyHTH( 3, 2 ); -acado_copyHTH( 4, 0 ); -acado_copyHTH( 4, 1 ); -acado_copyHTH( 4, 2 ); -acado_copyHTH( 4, 3 ); -acado_copyHTH( 5, 0 ); -acado_copyHTH( 5, 1 ); -acado_copyHTH( 5, 2 ); -acado_copyHTH( 5, 3 ); -acado_copyHTH( 5, 4 ); -acado_copyHTH( 6, 0 ); -acado_copyHTH( 6, 1 ); -acado_copyHTH( 6, 2 ); -acado_copyHTH( 6, 3 ); -acado_copyHTH( 6, 4 ); -acado_copyHTH( 6, 5 ); -acado_copyHTH( 7, 0 ); -acado_copyHTH( 7, 1 ); -acado_copyHTH( 7, 2 ); -acado_copyHTH( 7, 3 ); -acado_copyHTH( 7, 4 ); -acado_copyHTH( 7, 5 ); -acado_copyHTH( 7, 6 ); -acado_copyHTH( 8, 0 ); -acado_copyHTH( 8, 1 ); -acado_copyHTH( 8, 2 ); -acado_copyHTH( 8, 3 ); -acado_copyHTH( 8, 4 ); -acado_copyHTH( 8, 5 ); -acado_copyHTH( 8, 6 ); -acado_copyHTH( 8, 7 ); -acado_copyHTH( 9, 0 ); -acado_copyHTH( 9, 1 ); -acado_copyHTH( 9, 2 ); -acado_copyHTH( 9, 3 ); -acado_copyHTH( 9, 4 ); -acado_copyHTH( 9, 5 ); -acado_copyHTH( 9, 6 ); -acado_copyHTH( 9, 7 ); -acado_copyHTH( 9, 8 ); -acado_copyHTH( 10, 0 ); -acado_copyHTH( 10, 1 ); -acado_copyHTH( 10, 2 ); -acado_copyHTH( 10, 3 ); -acado_copyHTH( 10, 4 ); -acado_copyHTH( 10, 5 ); -acado_copyHTH( 10, 6 ); -acado_copyHTH( 10, 7 ); -acado_copyHTH( 10, 8 ); -acado_copyHTH( 10, 9 ); -acado_copyHTH( 11, 0 ); -acado_copyHTH( 11, 1 ); -acado_copyHTH( 11, 2 ); -acado_copyHTH( 11, 3 ); -acado_copyHTH( 11, 4 ); -acado_copyHTH( 11, 5 ); -acado_copyHTH( 11, 6 ); -acado_copyHTH( 11, 7 ); -acado_copyHTH( 11, 8 ); -acado_copyHTH( 11, 9 ); -acado_copyHTH( 11, 10 ); -acado_copyHTH( 12, 0 ); -acado_copyHTH( 12, 1 ); -acado_copyHTH( 12, 2 ); -acado_copyHTH( 12, 3 ); -acado_copyHTH( 12, 4 ); -acado_copyHTH( 12, 5 ); -acado_copyHTH( 12, 6 ); -acado_copyHTH( 12, 7 ); -acado_copyHTH( 12, 8 ); -acado_copyHTH( 12, 9 ); -acado_copyHTH( 12, 10 ); -acado_copyHTH( 12, 11 ); -acado_copyHTH( 13, 0 ); -acado_copyHTH( 13, 1 ); -acado_copyHTH( 13, 2 ); -acado_copyHTH( 13, 3 ); -acado_copyHTH( 13, 4 ); -acado_copyHTH( 13, 5 ); -acado_copyHTH( 13, 6 ); -acado_copyHTH( 13, 7 ); -acado_copyHTH( 13, 8 ); -acado_copyHTH( 13, 9 ); -acado_copyHTH( 13, 10 ); -acado_copyHTH( 13, 11 ); -acado_copyHTH( 13, 12 ); -acado_copyHTH( 14, 0 ); -acado_copyHTH( 14, 1 ); -acado_copyHTH( 14, 2 ); -acado_copyHTH( 14, 3 ); -acado_copyHTH( 14, 4 ); -acado_copyHTH( 14, 5 ); -acado_copyHTH( 14, 6 ); -acado_copyHTH( 14, 7 ); -acado_copyHTH( 14, 8 ); -acado_copyHTH( 14, 9 ); -acado_copyHTH( 14, 10 ); -acado_copyHTH( 14, 11 ); -acado_copyHTH( 14, 12 ); -acado_copyHTH( 14, 13 ); -acado_copyHTH( 15, 0 ); -acado_copyHTH( 15, 1 ); -acado_copyHTH( 15, 2 ); -acado_copyHTH( 15, 3 ); -acado_copyHTH( 15, 4 ); -acado_copyHTH( 15, 5 ); -acado_copyHTH( 15, 6 ); -acado_copyHTH( 15, 7 ); -acado_copyHTH( 15, 8 ); -acado_copyHTH( 15, 9 ); -acado_copyHTH( 15, 10 ); -acado_copyHTH( 15, 11 ); -acado_copyHTH( 15, 12 ); -acado_copyHTH( 15, 13 ); -acado_copyHTH( 15, 14 ); -acado_copyHTH( 16, 0 ); -acado_copyHTH( 16, 1 ); -acado_copyHTH( 16, 2 ); -acado_copyHTH( 16, 3 ); -acado_copyHTH( 16, 4 ); -acado_copyHTH( 16, 5 ); -acado_copyHTH( 16, 6 ); -acado_copyHTH( 16, 7 ); -acado_copyHTH( 16, 8 ); -acado_copyHTH( 16, 9 ); -acado_copyHTH( 16, 10 ); -acado_copyHTH( 16, 11 ); -acado_copyHTH( 16, 12 ); -acado_copyHTH( 16, 13 ); -acado_copyHTH( 16, 14 ); -acado_copyHTH( 16, 15 ); -acado_copyHTH( 17, 0 ); -acado_copyHTH( 17, 1 ); -acado_copyHTH( 17, 2 ); -acado_copyHTH( 17, 3 ); -acado_copyHTH( 17, 4 ); -acado_copyHTH( 17, 5 ); -acado_copyHTH( 17, 6 ); -acado_copyHTH( 17, 7 ); -acado_copyHTH( 17, 8 ); -acado_copyHTH( 17, 9 ); -acado_copyHTH( 17, 10 ); -acado_copyHTH( 17, 11 ); -acado_copyHTH( 17, 12 ); -acado_copyHTH( 17, 13 ); -acado_copyHTH( 17, 14 ); -acado_copyHTH( 17, 15 ); -acado_copyHTH( 17, 16 ); -acado_copyHTH( 18, 0 ); -acado_copyHTH( 18, 1 ); -acado_copyHTH( 18, 2 ); -acado_copyHTH( 18, 3 ); -acado_copyHTH( 18, 4 ); -acado_copyHTH( 18, 5 ); -acado_copyHTH( 18, 6 ); -acado_copyHTH( 18, 7 ); -acado_copyHTH( 18, 8 ); -acado_copyHTH( 18, 9 ); -acado_copyHTH( 18, 10 ); -acado_copyHTH( 18, 11 ); -acado_copyHTH( 18, 12 ); -acado_copyHTH( 18, 13 ); -acado_copyHTH( 18, 14 ); -acado_copyHTH( 18, 15 ); -acado_copyHTH( 18, 16 ); -acado_copyHTH( 18, 17 ); -acado_copyHTH( 19, 0 ); -acado_copyHTH( 19, 1 ); -acado_copyHTH( 19, 2 ); -acado_copyHTH( 19, 3 ); -acado_copyHTH( 19, 4 ); -acado_copyHTH( 19, 5 ); -acado_copyHTH( 19, 6 ); -acado_copyHTH( 19, 7 ); -acado_copyHTH( 19, 8 ); -acado_copyHTH( 19, 9 ); -acado_copyHTH( 19, 10 ); -acado_copyHTH( 19, 11 ); -acado_copyHTH( 19, 12 ); -acado_copyHTH( 19, 13 ); -acado_copyHTH( 19, 14 ); -acado_copyHTH( 19, 15 ); -acado_copyHTH( 19, 16 ); -acado_copyHTH( 19, 17 ); -acado_copyHTH( 19, 18 ); - -acadoWorkspace.H[96] = acadoWorkspace.H10[0]; -acadoWorkspace.H[97] = acadoWorkspace.H10[1]; -acadoWorkspace.H[98] = acadoWorkspace.H10[2]; -acadoWorkspace.H[99] = acadoWorkspace.H10[3]; -acadoWorkspace.H[120] = acadoWorkspace.H10[4]; -acadoWorkspace.H[121] = acadoWorkspace.H10[5]; -acadoWorkspace.H[122] = acadoWorkspace.H10[6]; -acadoWorkspace.H[123] = acadoWorkspace.H10[7]; -acadoWorkspace.H[144] = acadoWorkspace.H10[8]; -acadoWorkspace.H[145] = acadoWorkspace.H10[9]; -acadoWorkspace.H[146] = acadoWorkspace.H10[10]; -acadoWorkspace.H[147] = acadoWorkspace.H10[11]; -acadoWorkspace.H[168] = acadoWorkspace.H10[12]; -acadoWorkspace.H[169] = acadoWorkspace.H10[13]; -acadoWorkspace.H[170] = acadoWorkspace.H10[14]; -acadoWorkspace.H[171] = acadoWorkspace.H10[15]; -acadoWorkspace.H[192] = acadoWorkspace.H10[16]; -acadoWorkspace.H[193] = acadoWorkspace.H10[17]; -acadoWorkspace.H[194] = acadoWorkspace.H10[18]; -acadoWorkspace.H[195] = acadoWorkspace.H10[19]; -acadoWorkspace.H[216] = acadoWorkspace.H10[20]; -acadoWorkspace.H[217] = acadoWorkspace.H10[21]; -acadoWorkspace.H[218] = acadoWorkspace.H10[22]; -acadoWorkspace.H[219] = acadoWorkspace.H10[23]; -acadoWorkspace.H[240] = acadoWorkspace.H10[24]; -acadoWorkspace.H[241] = acadoWorkspace.H10[25]; -acadoWorkspace.H[242] = acadoWorkspace.H10[26]; -acadoWorkspace.H[243] = acadoWorkspace.H10[27]; -acadoWorkspace.H[264] = acadoWorkspace.H10[28]; -acadoWorkspace.H[265] = acadoWorkspace.H10[29]; -acadoWorkspace.H[266] = acadoWorkspace.H10[30]; -acadoWorkspace.H[267] = acadoWorkspace.H10[31]; -acadoWorkspace.H[288] = acadoWorkspace.H10[32]; -acadoWorkspace.H[289] = acadoWorkspace.H10[33]; -acadoWorkspace.H[290] = acadoWorkspace.H10[34]; -acadoWorkspace.H[291] = acadoWorkspace.H10[35]; -acadoWorkspace.H[312] = acadoWorkspace.H10[36]; -acadoWorkspace.H[313] = acadoWorkspace.H10[37]; -acadoWorkspace.H[314] = acadoWorkspace.H10[38]; -acadoWorkspace.H[315] = acadoWorkspace.H10[39]; -acadoWorkspace.H[336] = acadoWorkspace.H10[40]; -acadoWorkspace.H[337] = acadoWorkspace.H10[41]; -acadoWorkspace.H[338] = acadoWorkspace.H10[42]; -acadoWorkspace.H[339] = acadoWorkspace.H10[43]; -acadoWorkspace.H[360] = acadoWorkspace.H10[44]; -acadoWorkspace.H[361] = acadoWorkspace.H10[45]; -acadoWorkspace.H[362] = acadoWorkspace.H10[46]; -acadoWorkspace.H[363] = acadoWorkspace.H10[47]; -acadoWorkspace.H[384] = acadoWorkspace.H10[48]; -acadoWorkspace.H[385] = acadoWorkspace.H10[49]; -acadoWorkspace.H[386] = acadoWorkspace.H10[50]; -acadoWorkspace.H[387] = acadoWorkspace.H10[51]; -acadoWorkspace.H[408] = acadoWorkspace.H10[52]; -acadoWorkspace.H[409] = acadoWorkspace.H10[53]; -acadoWorkspace.H[410] = acadoWorkspace.H10[54]; -acadoWorkspace.H[411] = acadoWorkspace.H10[55]; -acadoWorkspace.H[432] = acadoWorkspace.H10[56]; -acadoWorkspace.H[433] = acadoWorkspace.H10[57]; -acadoWorkspace.H[434] = acadoWorkspace.H10[58]; -acadoWorkspace.H[435] = acadoWorkspace.H10[59]; -acadoWorkspace.H[456] = acadoWorkspace.H10[60]; -acadoWorkspace.H[457] = acadoWorkspace.H10[61]; -acadoWorkspace.H[458] = acadoWorkspace.H10[62]; -acadoWorkspace.H[459] = acadoWorkspace.H10[63]; -acadoWorkspace.H[480] = acadoWorkspace.H10[64]; -acadoWorkspace.H[481] = acadoWorkspace.H10[65]; -acadoWorkspace.H[482] = acadoWorkspace.H10[66]; -acadoWorkspace.H[483] = acadoWorkspace.H10[67]; -acadoWorkspace.H[504] = acadoWorkspace.H10[68]; -acadoWorkspace.H[505] = acadoWorkspace.H10[69]; -acadoWorkspace.H[506] = acadoWorkspace.H10[70]; -acadoWorkspace.H[507] = acadoWorkspace.H10[71]; -acadoWorkspace.H[528] = acadoWorkspace.H10[72]; -acadoWorkspace.H[529] = acadoWorkspace.H10[73]; -acadoWorkspace.H[530] = acadoWorkspace.H10[74]; -acadoWorkspace.H[531] = acadoWorkspace.H10[75]; -acadoWorkspace.H[552] = acadoWorkspace.H10[76]; -acadoWorkspace.H[553] = acadoWorkspace.H10[77]; -acadoWorkspace.H[554] = acadoWorkspace.H10[78]; -acadoWorkspace.H[555] = acadoWorkspace.H10[79]; - -acado_multQ1d( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.d, acadoWorkspace.Qd ); -acado_multQ1d( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.d[ 4 ]), &(acadoWorkspace.Qd[ 4 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.d[ 8 ]), &(acadoWorkspace.Qd[ 8 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.Qd[ 12 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.d[ 16 ]), &(acadoWorkspace.Qd[ 16 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.d[ 20 ]), &(acadoWorkspace.Qd[ 20 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.Qd[ 24 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.d[ 28 ]), &(acadoWorkspace.Qd[ 28 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.d[ 32 ]), &(acadoWorkspace.Qd[ 32 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.Qd[ 36 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.d[ 40 ]), &(acadoWorkspace.Qd[ 40 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.d[ 44 ]), &(acadoWorkspace.Qd[ 44 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.Qd[ 48 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.d[ 52 ]), &(acadoWorkspace.Qd[ 52 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.d[ 56 ]), &(acadoWorkspace.Qd[ 56 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.Qd[ 60 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.d[ 64 ]), &(acadoWorkspace.Qd[ 64 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.d[ 68 ]), &(acadoWorkspace.Qd[ 68 ]) ); -acado_multQ1d( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.Qd[ 72 ]) ); -acado_multQN1d( acadoWorkspace.QN1, &(acadoWorkspace.d[ 76 ]), &(acadoWorkspace.Qd[ 76 ]) ); - -acado_macCTSlx( acadoWorkspace.evGx, acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.g ); -acado_macCTSlx( &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.g ); -acado_macETSlu( acadoWorkspace.QE, &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 4 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 12 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 24 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 40 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 60 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 84 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 112 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 144 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 180 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 220 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 264 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 312 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 364 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 420 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 480 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 544 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 612 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 684 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 760 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 8 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 16 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 28 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 44 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 64 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 88 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 116 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 148 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 184 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 224 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 268 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 316 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 368 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 424 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 484 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 548 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 616 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 688 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 764 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 20 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 32 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 48 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 68 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 92 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 120 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 152 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 188 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 228 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 272 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 320 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 372 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 428 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 488 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 552 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 620 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 692 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 768 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 36 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 52 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 72 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 96 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 124 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 156 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 192 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 232 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 276 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 324 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 376 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 432 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 492 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 556 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 624 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 696 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 772 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 56 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 76 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 100 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 128 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 160 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 196 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 236 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 280 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 328 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 380 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 436 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 496 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 560 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 628 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 700 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 776 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 80 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 104 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 132 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 164 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 200 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 240 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 284 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 332 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 384 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 440 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 500 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 564 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 632 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 704 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 780 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 108 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 136 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 168 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 204 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 244 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 288 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 336 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 388 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 444 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 504 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 568 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 636 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 708 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 784 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 140 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 172 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 208 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 248 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 292 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 340 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 392 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 448 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 508 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 572 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 640 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 712 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 788 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 176 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 212 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 252 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 296 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 344 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 396 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 452 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 512 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 576 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 644 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 716 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 792 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 216 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 256 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 300 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 348 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 400 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 456 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 516 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 580 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 648 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 720 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 796 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 260 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 304 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 352 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 404 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 460 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 520 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 584 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 652 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 724 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 800 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 308 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 356 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 408 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 464 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 524 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 588 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 656 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 728 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 804 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 360 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 412 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 468 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 528 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 592 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 660 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 732 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 808 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 416 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 472 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 532 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 596 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 664 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 736 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 812 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 476 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 536 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 600 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 668 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 740 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 816 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 540 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 604 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 672 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 744 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 820 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 608 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 676 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 748 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 824 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 680 ]), &(acadoWorkspace.g[ 21 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 752 ]), &(acadoWorkspace.g[ 21 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 828 ]), &(acadoWorkspace.g[ 21 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 756 ]), &(acadoWorkspace.g[ 22 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 832 ]), &(acadoWorkspace.g[ 22 ]) ); -acado_macETSlu( &(acadoWorkspace.QE[ 836 ]), &(acadoWorkspace.g[ 23 ]) ); -acadoWorkspace.lb[4] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[0]; -acadoWorkspace.lb[5] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[1]; -acadoWorkspace.lb[6] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[2]; -acadoWorkspace.lb[7] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[3]; -acadoWorkspace.lb[8] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[4]; -acadoWorkspace.lb[9] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[5]; -acadoWorkspace.lb[10] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[6]; -acadoWorkspace.lb[11] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[7]; -acadoWorkspace.lb[12] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[8]; -acadoWorkspace.lb[13] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[9]; -acadoWorkspace.lb[14] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[10]; -acadoWorkspace.lb[15] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[11]; -acadoWorkspace.lb[16] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[12]; -acadoWorkspace.lb[17] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[13]; -acadoWorkspace.lb[18] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[14]; -acadoWorkspace.lb[19] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[15]; -acadoWorkspace.lb[20] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[16]; -acadoWorkspace.lb[21] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[17]; -acadoWorkspace.lb[22] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[18]; -acadoWorkspace.lb[23] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[19]; -acadoWorkspace.ub[4] = (real_t)1.0000000000000000e+12 - acadoVariables.u[0]; -acadoWorkspace.ub[5] = (real_t)1.0000000000000000e+12 - acadoVariables.u[1]; -acadoWorkspace.ub[6] = (real_t)1.0000000000000000e+12 - acadoVariables.u[2]; -acadoWorkspace.ub[7] = (real_t)1.0000000000000000e+12 - acadoVariables.u[3]; -acadoWorkspace.ub[8] = (real_t)1.0000000000000000e+12 - acadoVariables.u[4]; -acadoWorkspace.ub[9] = (real_t)1.0000000000000000e+12 - acadoVariables.u[5]; -acadoWorkspace.ub[10] = (real_t)1.0000000000000000e+12 - acadoVariables.u[6]; -acadoWorkspace.ub[11] = (real_t)1.0000000000000000e+12 - acadoVariables.u[7]; -acadoWorkspace.ub[12] = (real_t)1.0000000000000000e+12 - acadoVariables.u[8]; -acadoWorkspace.ub[13] = (real_t)1.0000000000000000e+12 - acadoVariables.u[9]; -acadoWorkspace.ub[14] = (real_t)1.0000000000000000e+12 - acadoVariables.u[10]; -acadoWorkspace.ub[15] = (real_t)1.0000000000000000e+12 - acadoVariables.u[11]; -acadoWorkspace.ub[16] = (real_t)1.0000000000000000e+12 - acadoVariables.u[12]; -acadoWorkspace.ub[17] = (real_t)1.0000000000000000e+12 - acadoVariables.u[13]; -acadoWorkspace.ub[18] = (real_t)1.0000000000000000e+12 - acadoVariables.u[14]; -acadoWorkspace.ub[19] = (real_t)1.0000000000000000e+12 - acadoVariables.u[15]; -acadoWorkspace.ub[20] = (real_t)1.0000000000000000e+12 - acadoVariables.u[16]; -acadoWorkspace.ub[21] = (real_t)1.0000000000000000e+12 - acadoVariables.u[17]; -acadoWorkspace.ub[22] = (real_t)1.0000000000000000e+12 - acadoVariables.u[18]; -acadoWorkspace.ub[23] = (real_t)1.0000000000000000e+12 - acadoVariables.u[19]; - -} - -void acado_condenseFdb( ) -{ -acadoWorkspace.Dx0[0] = acadoVariables.x0[0] - acadoVariables.x[0]; -acadoWorkspace.Dx0[1] = acadoVariables.x0[1] - acadoVariables.x[1]; -acadoWorkspace.Dx0[2] = acadoVariables.x0[2] - acadoVariables.x[2]; -acadoWorkspace.Dx0[3] = acadoVariables.x0[3] - acadoVariables.x[3]; - -acadoWorkspace.Dy[0] -= acadoVariables.y[0]; -acadoWorkspace.Dy[1] -= acadoVariables.y[1]; -acadoWorkspace.Dy[2] -= acadoVariables.y[2]; -acadoWorkspace.Dy[3] -= acadoVariables.y[3]; -acadoWorkspace.Dy[4] -= acadoVariables.y[4]; -acadoWorkspace.Dy[5] -= acadoVariables.y[5]; -acadoWorkspace.Dy[6] -= acadoVariables.y[6]; -acadoWorkspace.Dy[7] -= acadoVariables.y[7]; -acadoWorkspace.Dy[8] -= acadoVariables.y[8]; -acadoWorkspace.Dy[9] -= acadoVariables.y[9]; -acadoWorkspace.Dy[10] -= acadoVariables.y[10]; -acadoWorkspace.Dy[11] -= acadoVariables.y[11]; -acadoWorkspace.Dy[12] -= acadoVariables.y[12]; -acadoWorkspace.Dy[13] -= acadoVariables.y[13]; -acadoWorkspace.Dy[14] -= acadoVariables.y[14]; -acadoWorkspace.Dy[15] -= acadoVariables.y[15]; -acadoWorkspace.Dy[16] -= acadoVariables.y[16]; -acadoWorkspace.Dy[17] -= acadoVariables.y[17]; -acadoWorkspace.Dy[18] -= acadoVariables.y[18]; -acadoWorkspace.Dy[19] -= acadoVariables.y[19]; -acadoWorkspace.Dy[20] -= acadoVariables.y[20]; -acadoWorkspace.Dy[21] -= acadoVariables.y[21]; -acadoWorkspace.Dy[22] -= acadoVariables.y[22]; -acadoWorkspace.Dy[23] -= acadoVariables.y[23]; -acadoWorkspace.Dy[24] -= acadoVariables.y[24]; -acadoWorkspace.Dy[25] -= acadoVariables.y[25]; -acadoWorkspace.Dy[26] -= acadoVariables.y[26]; -acadoWorkspace.Dy[27] -= acadoVariables.y[27]; -acadoWorkspace.Dy[28] -= acadoVariables.y[28]; -acadoWorkspace.Dy[29] -= acadoVariables.y[29]; -acadoWorkspace.Dy[30] -= acadoVariables.y[30]; -acadoWorkspace.Dy[31] -= acadoVariables.y[31]; -acadoWorkspace.Dy[32] -= acadoVariables.y[32]; -acadoWorkspace.Dy[33] -= acadoVariables.y[33]; -acadoWorkspace.Dy[34] -= acadoVariables.y[34]; -acadoWorkspace.Dy[35] -= acadoVariables.y[35]; -acadoWorkspace.Dy[36] -= acadoVariables.y[36]; -acadoWorkspace.Dy[37] -= acadoVariables.y[37]; -acadoWorkspace.Dy[38] -= acadoVariables.y[38]; -acadoWorkspace.Dy[39] -= acadoVariables.y[39]; -acadoWorkspace.Dy[40] -= acadoVariables.y[40]; -acadoWorkspace.Dy[41] -= acadoVariables.y[41]; -acadoWorkspace.Dy[42] -= acadoVariables.y[42]; -acadoWorkspace.Dy[43] -= acadoVariables.y[43]; -acadoWorkspace.Dy[44] -= acadoVariables.y[44]; -acadoWorkspace.Dy[45] -= acadoVariables.y[45]; -acadoWorkspace.Dy[46] -= acadoVariables.y[46]; -acadoWorkspace.Dy[47] -= acadoVariables.y[47]; -acadoWorkspace.Dy[48] -= acadoVariables.y[48]; -acadoWorkspace.Dy[49] -= acadoVariables.y[49]; -acadoWorkspace.Dy[50] -= acadoVariables.y[50]; -acadoWorkspace.Dy[51] -= acadoVariables.y[51]; -acadoWorkspace.Dy[52] -= acadoVariables.y[52]; -acadoWorkspace.Dy[53] -= acadoVariables.y[53]; -acadoWorkspace.Dy[54] -= acadoVariables.y[54]; -acadoWorkspace.Dy[55] -= acadoVariables.y[55]; -acadoWorkspace.Dy[56] -= acadoVariables.y[56]; -acadoWorkspace.Dy[57] -= acadoVariables.y[57]; -acadoWorkspace.Dy[58] -= acadoVariables.y[58]; -acadoWorkspace.Dy[59] -= acadoVariables.y[59]; -acadoWorkspace.Dy[60] -= acadoVariables.y[60]; -acadoWorkspace.Dy[61] -= acadoVariables.y[61]; -acadoWorkspace.Dy[62] -= acadoVariables.y[62]; -acadoWorkspace.Dy[63] -= acadoVariables.y[63]; -acadoWorkspace.Dy[64] -= acadoVariables.y[64]; -acadoWorkspace.Dy[65] -= acadoVariables.y[65]; -acadoWorkspace.Dy[66] -= acadoVariables.y[66]; -acadoWorkspace.Dy[67] -= acadoVariables.y[67]; -acadoWorkspace.Dy[68] -= acadoVariables.y[68]; -acadoWorkspace.Dy[69] -= acadoVariables.y[69]; -acadoWorkspace.Dy[70] -= acadoVariables.y[70]; -acadoWorkspace.Dy[71] -= acadoVariables.y[71]; -acadoWorkspace.Dy[72] -= acadoVariables.y[72]; -acadoWorkspace.Dy[73] -= acadoVariables.y[73]; -acadoWorkspace.Dy[74] -= acadoVariables.y[74]; -acadoWorkspace.Dy[75] -= acadoVariables.y[75]; -acadoWorkspace.Dy[76] -= acadoVariables.y[76]; -acadoWorkspace.Dy[77] -= acadoVariables.y[77]; -acadoWorkspace.Dy[78] -= acadoVariables.y[78]; -acadoWorkspace.Dy[79] -= acadoVariables.y[79]; -acadoWorkspace.Dy[80] -= acadoVariables.y[80]; -acadoWorkspace.Dy[81] -= acadoVariables.y[81]; -acadoWorkspace.Dy[82] -= acadoVariables.y[82]; -acadoWorkspace.Dy[83] -= acadoVariables.y[83]; -acadoWorkspace.Dy[84] -= acadoVariables.y[84]; -acadoWorkspace.Dy[85] -= acadoVariables.y[85]; -acadoWorkspace.Dy[86] -= acadoVariables.y[86]; -acadoWorkspace.Dy[87] -= acadoVariables.y[87]; -acadoWorkspace.Dy[88] -= acadoVariables.y[88]; -acadoWorkspace.Dy[89] -= acadoVariables.y[89]; -acadoWorkspace.Dy[90] -= acadoVariables.y[90]; -acadoWorkspace.Dy[91] -= acadoVariables.y[91]; -acadoWorkspace.Dy[92] -= acadoVariables.y[92]; -acadoWorkspace.Dy[93] -= acadoVariables.y[93]; -acadoWorkspace.Dy[94] -= acadoVariables.y[94]; -acadoWorkspace.Dy[95] -= acadoVariables.y[95]; -acadoWorkspace.Dy[96] -= acadoVariables.y[96]; -acadoWorkspace.Dy[97] -= acadoVariables.y[97]; -acadoWorkspace.Dy[98] -= acadoVariables.y[98]; -acadoWorkspace.Dy[99] -= acadoVariables.y[99]; -acadoWorkspace.DyN[0] -= acadoVariables.yN[0]; -acadoWorkspace.DyN[1] -= acadoVariables.yN[1]; -acadoWorkspace.DyN[2] -= acadoVariables.yN[2]; -acadoWorkspace.DyN[3] -= acadoVariables.yN[3]; - -acado_multRDy( acadoWorkspace.R2, acadoWorkspace.Dy, &(acadoWorkspace.g[ 4 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 5 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 10 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 15 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 20 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 25 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 30 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 35 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 40 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 45 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 50 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 55 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 60 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 65 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 70 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 75 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 80 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 85 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.g[ 21 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 90 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.g[ 22 ]) ); -acado_multRDy( &(acadoWorkspace.R2[ 95 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.g[ 23 ]) ); - -acado_multQDy( acadoWorkspace.Q2, acadoWorkspace.Dy, acadoWorkspace.QDy ); -acado_multQDy( &(acadoWorkspace.Q2[ 20 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.QDy[ 4 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 40 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.QDy[ 8 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 60 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.QDy[ 12 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 80 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.QDy[ 16 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 100 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.QDy[ 20 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 120 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.QDy[ 24 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 140 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.QDy[ 28 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 160 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.QDy[ 32 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 180 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.QDy[ 36 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 200 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.QDy[ 40 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 220 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.QDy[ 44 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 240 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.QDy[ 48 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 260 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.QDy[ 52 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 280 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.QDy[ 56 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 300 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.QDy[ 60 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 320 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.QDy[ 64 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 340 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.QDy[ 68 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 360 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.QDy[ 72 ]) ); -acado_multQDy( &(acadoWorkspace.Q2[ 380 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.QDy[ 76 ]) ); - -acadoWorkspace.QDy[80] = + acadoWorkspace.QN2[0]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[1]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[2]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[3]*acadoWorkspace.DyN[3]; -acadoWorkspace.QDy[81] = + acadoWorkspace.QN2[4]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[5]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[6]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[7]*acadoWorkspace.DyN[3]; -acadoWorkspace.QDy[82] = + acadoWorkspace.QN2[8]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[9]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[10]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[11]*acadoWorkspace.DyN[3]; -acadoWorkspace.QDy[83] = + acadoWorkspace.QN2[12]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[13]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[14]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[15]*acadoWorkspace.DyN[3]; - -acadoWorkspace.QDy[4] += acadoWorkspace.Qd[0]; -acadoWorkspace.QDy[5] += acadoWorkspace.Qd[1]; -acadoWorkspace.QDy[6] += acadoWorkspace.Qd[2]; -acadoWorkspace.QDy[7] += acadoWorkspace.Qd[3]; -acadoWorkspace.QDy[8] += acadoWorkspace.Qd[4]; -acadoWorkspace.QDy[9] += acadoWorkspace.Qd[5]; -acadoWorkspace.QDy[10] += acadoWorkspace.Qd[6]; -acadoWorkspace.QDy[11] += acadoWorkspace.Qd[7]; -acadoWorkspace.QDy[12] += acadoWorkspace.Qd[8]; -acadoWorkspace.QDy[13] += acadoWorkspace.Qd[9]; -acadoWorkspace.QDy[14] += acadoWorkspace.Qd[10]; -acadoWorkspace.QDy[15] += acadoWorkspace.Qd[11]; -acadoWorkspace.QDy[16] += acadoWorkspace.Qd[12]; -acadoWorkspace.QDy[17] += acadoWorkspace.Qd[13]; -acadoWorkspace.QDy[18] += acadoWorkspace.Qd[14]; -acadoWorkspace.QDy[19] += acadoWorkspace.Qd[15]; -acadoWorkspace.QDy[20] += acadoWorkspace.Qd[16]; -acadoWorkspace.QDy[21] += acadoWorkspace.Qd[17]; -acadoWorkspace.QDy[22] += acadoWorkspace.Qd[18]; -acadoWorkspace.QDy[23] += acadoWorkspace.Qd[19]; -acadoWorkspace.QDy[24] += acadoWorkspace.Qd[20]; -acadoWorkspace.QDy[25] += acadoWorkspace.Qd[21]; -acadoWorkspace.QDy[26] += acadoWorkspace.Qd[22]; -acadoWorkspace.QDy[27] += acadoWorkspace.Qd[23]; -acadoWorkspace.QDy[28] += acadoWorkspace.Qd[24]; -acadoWorkspace.QDy[29] += acadoWorkspace.Qd[25]; -acadoWorkspace.QDy[30] += acadoWorkspace.Qd[26]; -acadoWorkspace.QDy[31] += acadoWorkspace.Qd[27]; -acadoWorkspace.QDy[32] += acadoWorkspace.Qd[28]; -acadoWorkspace.QDy[33] += acadoWorkspace.Qd[29]; -acadoWorkspace.QDy[34] += acadoWorkspace.Qd[30]; -acadoWorkspace.QDy[35] += acadoWorkspace.Qd[31]; -acadoWorkspace.QDy[36] += acadoWorkspace.Qd[32]; -acadoWorkspace.QDy[37] += acadoWorkspace.Qd[33]; -acadoWorkspace.QDy[38] += acadoWorkspace.Qd[34]; -acadoWorkspace.QDy[39] += acadoWorkspace.Qd[35]; -acadoWorkspace.QDy[40] += acadoWorkspace.Qd[36]; -acadoWorkspace.QDy[41] += acadoWorkspace.Qd[37]; -acadoWorkspace.QDy[42] += acadoWorkspace.Qd[38]; -acadoWorkspace.QDy[43] += acadoWorkspace.Qd[39]; -acadoWorkspace.QDy[44] += acadoWorkspace.Qd[40]; -acadoWorkspace.QDy[45] += acadoWorkspace.Qd[41]; -acadoWorkspace.QDy[46] += acadoWorkspace.Qd[42]; -acadoWorkspace.QDy[47] += acadoWorkspace.Qd[43]; -acadoWorkspace.QDy[48] += acadoWorkspace.Qd[44]; -acadoWorkspace.QDy[49] += acadoWorkspace.Qd[45]; -acadoWorkspace.QDy[50] += acadoWorkspace.Qd[46]; -acadoWorkspace.QDy[51] += acadoWorkspace.Qd[47]; -acadoWorkspace.QDy[52] += acadoWorkspace.Qd[48]; -acadoWorkspace.QDy[53] += acadoWorkspace.Qd[49]; -acadoWorkspace.QDy[54] += acadoWorkspace.Qd[50]; -acadoWorkspace.QDy[55] += acadoWorkspace.Qd[51]; -acadoWorkspace.QDy[56] += acadoWorkspace.Qd[52]; -acadoWorkspace.QDy[57] += acadoWorkspace.Qd[53]; -acadoWorkspace.QDy[58] += acadoWorkspace.Qd[54]; -acadoWorkspace.QDy[59] += acadoWorkspace.Qd[55]; -acadoWorkspace.QDy[60] += acadoWorkspace.Qd[56]; -acadoWorkspace.QDy[61] += acadoWorkspace.Qd[57]; -acadoWorkspace.QDy[62] += acadoWorkspace.Qd[58]; -acadoWorkspace.QDy[63] += acadoWorkspace.Qd[59]; -acadoWorkspace.QDy[64] += acadoWorkspace.Qd[60]; -acadoWorkspace.QDy[65] += acadoWorkspace.Qd[61]; -acadoWorkspace.QDy[66] += acadoWorkspace.Qd[62]; -acadoWorkspace.QDy[67] += acadoWorkspace.Qd[63]; -acadoWorkspace.QDy[68] += acadoWorkspace.Qd[64]; -acadoWorkspace.QDy[69] += acadoWorkspace.Qd[65]; -acadoWorkspace.QDy[70] += acadoWorkspace.Qd[66]; -acadoWorkspace.QDy[71] += acadoWorkspace.Qd[67]; -acadoWorkspace.QDy[72] += acadoWorkspace.Qd[68]; -acadoWorkspace.QDy[73] += acadoWorkspace.Qd[69]; -acadoWorkspace.QDy[74] += acadoWorkspace.Qd[70]; -acadoWorkspace.QDy[75] += acadoWorkspace.Qd[71]; -acadoWorkspace.QDy[76] += acadoWorkspace.Qd[72]; -acadoWorkspace.QDy[77] += acadoWorkspace.Qd[73]; -acadoWorkspace.QDy[78] += acadoWorkspace.Qd[74]; -acadoWorkspace.QDy[79] += acadoWorkspace.Qd[75]; -acadoWorkspace.QDy[80] += acadoWorkspace.Qd[76]; -acadoWorkspace.QDy[81] += acadoWorkspace.Qd[77]; -acadoWorkspace.QDy[82] += acadoWorkspace.Qd[78]; -acadoWorkspace.QDy[83] += acadoWorkspace.Qd[79]; - -acadoWorkspace.g[0] = + acadoWorkspace.evGx[0]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[4]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[8]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[12]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[16]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[20]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[24]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[28]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[32]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[36]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[40]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[44]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[48]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[52]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[56]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[60]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[64]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[68]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[72]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[76]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[80]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[84]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[88]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[92]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[96]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[100]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[104]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[108]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[112]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[116]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[120]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[124]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[128]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[132]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[136]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[140]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[144]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[148]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[152]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[156]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[160]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[164]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[168]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[172]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[176]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[180]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[184]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[188]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[192]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[196]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[200]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[204]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[208]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[212]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[216]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[220]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[224]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[228]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[232]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[236]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[240]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[244]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[248]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[252]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[256]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[260]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[264]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[268]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[272]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[276]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[280]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[284]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[288]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[292]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[296]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[300]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[304]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[308]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[312]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[316]*acadoWorkspace.QDy[83]; -acadoWorkspace.g[1] = + acadoWorkspace.evGx[1]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[5]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[9]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[13]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[17]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[21]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[25]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[29]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[33]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[37]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[41]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[45]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[49]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[53]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[57]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[61]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[65]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[69]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[73]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[77]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[81]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[85]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[89]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[93]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[97]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[101]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[105]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[109]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[113]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[117]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[121]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[125]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[129]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[133]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[137]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[141]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[145]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[149]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[153]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[157]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[161]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[165]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[169]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[173]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[177]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[181]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[185]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[189]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[193]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[197]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[201]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[205]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[209]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[213]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[217]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[221]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[225]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[229]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[233]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[237]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[241]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[245]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[249]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[253]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[257]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[261]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[265]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[269]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[273]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[277]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[281]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[285]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[289]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[293]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[297]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[301]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[305]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[309]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[313]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[317]*acadoWorkspace.QDy[83]; -acadoWorkspace.g[2] = + acadoWorkspace.evGx[2]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[6]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[10]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[14]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[18]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[22]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[26]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[30]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[34]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[38]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[42]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[46]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[50]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[54]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[58]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[62]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[66]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[70]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[74]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[78]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[82]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[86]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[90]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[94]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[98]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[102]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[106]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[110]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[114]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[118]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[122]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[126]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[130]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[134]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[138]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[142]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[146]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[150]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[154]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[158]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[162]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[166]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[170]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[174]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[178]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[182]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[186]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[190]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[194]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[198]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[202]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[206]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[210]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[214]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[218]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[222]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[226]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[230]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[234]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[238]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[242]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[246]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[250]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[254]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[258]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[262]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[266]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[270]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[274]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[278]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[282]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[286]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[290]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[294]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[298]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[302]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[306]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[310]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[314]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[318]*acadoWorkspace.QDy[83]; -acadoWorkspace.g[3] = + acadoWorkspace.evGx[3]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[7]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[11]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[15]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[19]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[23]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[27]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[31]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[35]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[39]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[43]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[47]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[51]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[55]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[59]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[63]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[67]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[71]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[75]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[79]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[83]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[87]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[91]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[95]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[99]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[103]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[107]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[111]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[115]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[119]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[123]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[127]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[131]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[135]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[139]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[143]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[147]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[151]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[155]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[159]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[163]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[167]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[171]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[175]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[179]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[183]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[187]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[191]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[195]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[199]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[203]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[207]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[211]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[215]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[219]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[223]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[227]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[231]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[235]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[239]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[243]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[247]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[251]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[255]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[259]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[263]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[267]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[271]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[275]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[279]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[283]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[287]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[291]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[295]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[299]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[303]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[307]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[311]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[315]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[319]*acadoWorkspace.QDy[83]; - - -acado_multEQDy( acadoWorkspace.E, &(acadoWorkspace.QDy[ 4 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QDy[ 8 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 4 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.QDy[ 8 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 5 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 6 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 7 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 8 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 9 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 10 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 11 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 12 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 13 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 14 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 15 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 16 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 17 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 18 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 19 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 20 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 21 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 21 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 21 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 22 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 22 ]) ); -acado_multEQDy( &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 23 ]) ); - -acadoWorkspace.lb[0] = acadoWorkspace.Dx0[0]; -acadoWorkspace.lb[1] = acadoWorkspace.Dx0[1]; -acadoWorkspace.lb[2] = acadoWorkspace.Dx0[2]; -acadoWorkspace.lb[3] = acadoWorkspace.Dx0[3]; -acadoWorkspace.ub[0] = acadoWorkspace.Dx0[0]; -acadoWorkspace.ub[1] = acadoWorkspace.Dx0[1]; -acadoWorkspace.ub[2] = acadoWorkspace.Dx0[2]; -acadoWorkspace.ub[3] = acadoWorkspace.Dx0[3]; -} - -void acado_expand( ) -{ -acadoVariables.x[0] += acadoWorkspace.x[0]; -acadoVariables.x[1] += acadoWorkspace.x[1]; -acadoVariables.x[2] += acadoWorkspace.x[2]; -acadoVariables.x[3] += acadoWorkspace.x[3]; - -acadoVariables.u[0] += acadoWorkspace.x[4]; -acadoVariables.u[1] += acadoWorkspace.x[5]; -acadoVariables.u[2] += acadoWorkspace.x[6]; -acadoVariables.u[3] += acadoWorkspace.x[7]; -acadoVariables.u[4] += acadoWorkspace.x[8]; -acadoVariables.u[5] += acadoWorkspace.x[9]; -acadoVariables.u[6] += acadoWorkspace.x[10]; -acadoVariables.u[7] += acadoWorkspace.x[11]; -acadoVariables.u[8] += acadoWorkspace.x[12]; -acadoVariables.u[9] += acadoWorkspace.x[13]; -acadoVariables.u[10] += acadoWorkspace.x[14]; -acadoVariables.u[11] += acadoWorkspace.x[15]; -acadoVariables.u[12] += acadoWorkspace.x[16]; -acadoVariables.u[13] += acadoWorkspace.x[17]; -acadoVariables.u[14] += acadoWorkspace.x[18]; -acadoVariables.u[15] += acadoWorkspace.x[19]; -acadoVariables.u[16] += acadoWorkspace.x[20]; -acadoVariables.u[17] += acadoWorkspace.x[21]; -acadoVariables.u[18] += acadoWorkspace.x[22]; -acadoVariables.u[19] += acadoWorkspace.x[23]; - -acadoVariables.x[4] += + acadoWorkspace.evGx[0]*acadoWorkspace.x[0] + acadoWorkspace.evGx[1]*acadoWorkspace.x[1] + acadoWorkspace.evGx[2]*acadoWorkspace.x[2] + acadoWorkspace.evGx[3]*acadoWorkspace.x[3] + acadoWorkspace.d[0]; -acadoVariables.x[5] += + acadoWorkspace.evGx[4]*acadoWorkspace.x[0] + acadoWorkspace.evGx[5]*acadoWorkspace.x[1] + acadoWorkspace.evGx[6]*acadoWorkspace.x[2] + acadoWorkspace.evGx[7]*acadoWorkspace.x[3] + acadoWorkspace.d[1]; -acadoVariables.x[6] += + acadoWorkspace.evGx[8]*acadoWorkspace.x[0] + acadoWorkspace.evGx[9]*acadoWorkspace.x[1] + acadoWorkspace.evGx[10]*acadoWorkspace.x[2] + acadoWorkspace.evGx[11]*acadoWorkspace.x[3] + acadoWorkspace.d[2]; -acadoVariables.x[7] += + acadoWorkspace.evGx[12]*acadoWorkspace.x[0] + acadoWorkspace.evGx[13]*acadoWorkspace.x[1] + acadoWorkspace.evGx[14]*acadoWorkspace.x[2] + acadoWorkspace.evGx[15]*acadoWorkspace.x[3] + acadoWorkspace.d[3]; -acadoVariables.x[8] += + acadoWorkspace.evGx[16]*acadoWorkspace.x[0] + acadoWorkspace.evGx[17]*acadoWorkspace.x[1] + acadoWorkspace.evGx[18]*acadoWorkspace.x[2] + acadoWorkspace.evGx[19]*acadoWorkspace.x[3] + acadoWorkspace.d[4]; -acadoVariables.x[9] += + acadoWorkspace.evGx[20]*acadoWorkspace.x[0] + acadoWorkspace.evGx[21]*acadoWorkspace.x[1] + acadoWorkspace.evGx[22]*acadoWorkspace.x[2] + acadoWorkspace.evGx[23]*acadoWorkspace.x[3] + acadoWorkspace.d[5]; -acadoVariables.x[10] += + acadoWorkspace.evGx[24]*acadoWorkspace.x[0] + acadoWorkspace.evGx[25]*acadoWorkspace.x[1] + acadoWorkspace.evGx[26]*acadoWorkspace.x[2] + acadoWorkspace.evGx[27]*acadoWorkspace.x[3] + acadoWorkspace.d[6]; -acadoVariables.x[11] += + acadoWorkspace.evGx[28]*acadoWorkspace.x[0] + acadoWorkspace.evGx[29]*acadoWorkspace.x[1] + acadoWorkspace.evGx[30]*acadoWorkspace.x[2] + acadoWorkspace.evGx[31]*acadoWorkspace.x[3] + acadoWorkspace.d[7]; -acadoVariables.x[12] += + acadoWorkspace.evGx[32]*acadoWorkspace.x[0] + acadoWorkspace.evGx[33]*acadoWorkspace.x[1] + acadoWorkspace.evGx[34]*acadoWorkspace.x[2] + acadoWorkspace.evGx[35]*acadoWorkspace.x[3] + acadoWorkspace.d[8]; -acadoVariables.x[13] += + acadoWorkspace.evGx[36]*acadoWorkspace.x[0] + acadoWorkspace.evGx[37]*acadoWorkspace.x[1] + acadoWorkspace.evGx[38]*acadoWorkspace.x[2] + acadoWorkspace.evGx[39]*acadoWorkspace.x[3] + acadoWorkspace.d[9]; -acadoVariables.x[14] += + acadoWorkspace.evGx[40]*acadoWorkspace.x[0] + acadoWorkspace.evGx[41]*acadoWorkspace.x[1] + acadoWorkspace.evGx[42]*acadoWorkspace.x[2] + acadoWorkspace.evGx[43]*acadoWorkspace.x[3] + acadoWorkspace.d[10]; -acadoVariables.x[15] += + acadoWorkspace.evGx[44]*acadoWorkspace.x[0] + acadoWorkspace.evGx[45]*acadoWorkspace.x[1] + acadoWorkspace.evGx[46]*acadoWorkspace.x[2] + acadoWorkspace.evGx[47]*acadoWorkspace.x[3] + acadoWorkspace.d[11]; -acadoVariables.x[16] += + acadoWorkspace.evGx[48]*acadoWorkspace.x[0] + acadoWorkspace.evGx[49]*acadoWorkspace.x[1] + acadoWorkspace.evGx[50]*acadoWorkspace.x[2] + acadoWorkspace.evGx[51]*acadoWorkspace.x[3] + acadoWorkspace.d[12]; -acadoVariables.x[17] += + acadoWorkspace.evGx[52]*acadoWorkspace.x[0] + acadoWorkspace.evGx[53]*acadoWorkspace.x[1] + acadoWorkspace.evGx[54]*acadoWorkspace.x[2] + acadoWorkspace.evGx[55]*acadoWorkspace.x[3] + acadoWorkspace.d[13]; -acadoVariables.x[18] += + acadoWorkspace.evGx[56]*acadoWorkspace.x[0] + acadoWorkspace.evGx[57]*acadoWorkspace.x[1] + acadoWorkspace.evGx[58]*acadoWorkspace.x[2] + acadoWorkspace.evGx[59]*acadoWorkspace.x[3] + acadoWorkspace.d[14]; -acadoVariables.x[19] += + acadoWorkspace.evGx[60]*acadoWorkspace.x[0] + acadoWorkspace.evGx[61]*acadoWorkspace.x[1] + acadoWorkspace.evGx[62]*acadoWorkspace.x[2] + acadoWorkspace.evGx[63]*acadoWorkspace.x[3] + acadoWorkspace.d[15]; -acadoVariables.x[20] += + acadoWorkspace.evGx[64]*acadoWorkspace.x[0] + acadoWorkspace.evGx[65]*acadoWorkspace.x[1] + acadoWorkspace.evGx[66]*acadoWorkspace.x[2] + acadoWorkspace.evGx[67]*acadoWorkspace.x[3] + acadoWorkspace.d[16]; -acadoVariables.x[21] += + acadoWorkspace.evGx[68]*acadoWorkspace.x[0] + acadoWorkspace.evGx[69]*acadoWorkspace.x[1] + acadoWorkspace.evGx[70]*acadoWorkspace.x[2] + acadoWorkspace.evGx[71]*acadoWorkspace.x[3] + acadoWorkspace.d[17]; -acadoVariables.x[22] += + acadoWorkspace.evGx[72]*acadoWorkspace.x[0] + acadoWorkspace.evGx[73]*acadoWorkspace.x[1] + acadoWorkspace.evGx[74]*acadoWorkspace.x[2] + acadoWorkspace.evGx[75]*acadoWorkspace.x[3] + acadoWorkspace.d[18]; -acadoVariables.x[23] += + acadoWorkspace.evGx[76]*acadoWorkspace.x[0] + acadoWorkspace.evGx[77]*acadoWorkspace.x[1] + acadoWorkspace.evGx[78]*acadoWorkspace.x[2] + acadoWorkspace.evGx[79]*acadoWorkspace.x[3] + acadoWorkspace.d[19]; -acadoVariables.x[24] += + acadoWorkspace.evGx[80]*acadoWorkspace.x[0] + acadoWorkspace.evGx[81]*acadoWorkspace.x[1] + acadoWorkspace.evGx[82]*acadoWorkspace.x[2] + acadoWorkspace.evGx[83]*acadoWorkspace.x[3] + acadoWorkspace.d[20]; -acadoVariables.x[25] += + acadoWorkspace.evGx[84]*acadoWorkspace.x[0] + acadoWorkspace.evGx[85]*acadoWorkspace.x[1] + acadoWorkspace.evGx[86]*acadoWorkspace.x[2] + acadoWorkspace.evGx[87]*acadoWorkspace.x[3] + acadoWorkspace.d[21]; -acadoVariables.x[26] += + acadoWorkspace.evGx[88]*acadoWorkspace.x[0] + acadoWorkspace.evGx[89]*acadoWorkspace.x[1] + acadoWorkspace.evGx[90]*acadoWorkspace.x[2] + acadoWorkspace.evGx[91]*acadoWorkspace.x[3] + acadoWorkspace.d[22]; -acadoVariables.x[27] += + acadoWorkspace.evGx[92]*acadoWorkspace.x[0] + acadoWorkspace.evGx[93]*acadoWorkspace.x[1] + acadoWorkspace.evGx[94]*acadoWorkspace.x[2] + acadoWorkspace.evGx[95]*acadoWorkspace.x[3] + acadoWorkspace.d[23]; -acadoVariables.x[28] += + acadoWorkspace.evGx[96]*acadoWorkspace.x[0] + acadoWorkspace.evGx[97]*acadoWorkspace.x[1] + acadoWorkspace.evGx[98]*acadoWorkspace.x[2] + acadoWorkspace.evGx[99]*acadoWorkspace.x[3] + acadoWorkspace.d[24]; -acadoVariables.x[29] += + acadoWorkspace.evGx[100]*acadoWorkspace.x[0] + acadoWorkspace.evGx[101]*acadoWorkspace.x[1] + acadoWorkspace.evGx[102]*acadoWorkspace.x[2] + acadoWorkspace.evGx[103]*acadoWorkspace.x[3] + acadoWorkspace.d[25]; -acadoVariables.x[30] += + acadoWorkspace.evGx[104]*acadoWorkspace.x[0] + acadoWorkspace.evGx[105]*acadoWorkspace.x[1] + acadoWorkspace.evGx[106]*acadoWorkspace.x[2] + acadoWorkspace.evGx[107]*acadoWorkspace.x[3] + acadoWorkspace.d[26]; -acadoVariables.x[31] += + acadoWorkspace.evGx[108]*acadoWorkspace.x[0] + acadoWorkspace.evGx[109]*acadoWorkspace.x[1] + acadoWorkspace.evGx[110]*acadoWorkspace.x[2] + acadoWorkspace.evGx[111]*acadoWorkspace.x[3] + acadoWorkspace.d[27]; -acadoVariables.x[32] += + acadoWorkspace.evGx[112]*acadoWorkspace.x[0] + acadoWorkspace.evGx[113]*acadoWorkspace.x[1] + acadoWorkspace.evGx[114]*acadoWorkspace.x[2] + acadoWorkspace.evGx[115]*acadoWorkspace.x[3] + acadoWorkspace.d[28]; -acadoVariables.x[33] += + acadoWorkspace.evGx[116]*acadoWorkspace.x[0] + acadoWorkspace.evGx[117]*acadoWorkspace.x[1] + acadoWorkspace.evGx[118]*acadoWorkspace.x[2] + acadoWorkspace.evGx[119]*acadoWorkspace.x[3] + acadoWorkspace.d[29]; -acadoVariables.x[34] += + acadoWorkspace.evGx[120]*acadoWorkspace.x[0] + acadoWorkspace.evGx[121]*acadoWorkspace.x[1] + acadoWorkspace.evGx[122]*acadoWorkspace.x[2] + acadoWorkspace.evGx[123]*acadoWorkspace.x[3] + acadoWorkspace.d[30]; -acadoVariables.x[35] += + acadoWorkspace.evGx[124]*acadoWorkspace.x[0] + acadoWorkspace.evGx[125]*acadoWorkspace.x[1] + acadoWorkspace.evGx[126]*acadoWorkspace.x[2] + acadoWorkspace.evGx[127]*acadoWorkspace.x[3] + acadoWorkspace.d[31]; -acadoVariables.x[36] += + acadoWorkspace.evGx[128]*acadoWorkspace.x[0] + acadoWorkspace.evGx[129]*acadoWorkspace.x[1] + acadoWorkspace.evGx[130]*acadoWorkspace.x[2] + acadoWorkspace.evGx[131]*acadoWorkspace.x[3] + acadoWorkspace.d[32]; -acadoVariables.x[37] += + acadoWorkspace.evGx[132]*acadoWorkspace.x[0] + acadoWorkspace.evGx[133]*acadoWorkspace.x[1] + acadoWorkspace.evGx[134]*acadoWorkspace.x[2] + acadoWorkspace.evGx[135]*acadoWorkspace.x[3] + acadoWorkspace.d[33]; -acadoVariables.x[38] += + acadoWorkspace.evGx[136]*acadoWorkspace.x[0] + acadoWorkspace.evGx[137]*acadoWorkspace.x[1] + acadoWorkspace.evGx[138]*acadoWorkspace.x[2] + acadoWorkspace.evGx[139]*acadoWorkspace.x[3] + acadoWorkspace.d[34]; -acadoVariables.x[39] += + acadoWorkspace.evGx[140]*acadoWorkspace.x[0] + acadoWorkspace.evGx[141]*acadoWorkspace.x[1] + acadoWorkspace.evGx[142]*acadoWorkspace.x[2] + acadoWorkspace.evGx[143]*acadoWorkspace.x[3] + acadoWorkspace.d[35]; -acadoVariables.x[40] += + acadoWorkspace.evGx[144]*acadoWorkspace.x[0] + acadoWorkspace.evGx[145]*acadoWorkspace.x[1] + acadoWorkspace.evGx[146]*acadoWorkspace.x[2] + acadoWorkspace.evGx[147]*acadoWorkspace.x[3] + acadoWorkspace.d[36]; -acadoVariables.x[41] += + acadoWorkspace.evGx[148]*acadoWorkspace.x[0] + acadoWorkspace.evGx[149]*acadoWorkspace.x[1] + acadoWorkspace.evGx[150]*acadoWorkspace.x[2] + acadoWorkspace.evGx[151]*acadoWorkspace.x[3] + acadoWorkspace.d[37]; -acadoVariables.x[42] += + acadoWorkspace.evGx[152]*acadoWorkspace.x[0] + acadoWorkspace.evGx[153]*acadoWorkspace.x[1] + acadoWorkspace.evGx[154]*acadoWorkspace.x[2] + acadoWorkspace.evGx[155]*acadoWorkspace.x[3] + acadoWorkspace.d[38]; -acadoVariables.x[43] += + acadoWorkspace.evGx[156]*acadoWorkspace.x[0] + acadoWorkspace.evGx[157]*acadoWorkspace.x[1] + acadoWorkspace.evGx[158]*acadoWorkspace.x[2] + acadoWorkspace.evGx[159]*acadoWorkspace.x[3] + acadoWorkspace.d[39]; -acadoVariables.x[44] += + acadoWorkspace.evGx[160]*acadoWorkspace.x[0] + acadoWorkspace.evGx[161]*acadoWorkspace.x[1] + acadoWorkspace.evGx[162]*acadoWorkspace.x[2] + acadoWorkspace.evGx[163]*acadoWorkspace.x[3] + acadoWorkspace.d[40]; -acadoVariables.x[45] += + acadoWorkspace.evGx[164]*acadoWorkspace.x[0] + acadoWorkspace.evGx[165]*acadoWorkspace.x[1] + acadoWorkspace.evGx[166]*acadoWorkspace.x[2] + acadoWorkspace.evGx[167]*acadoWorkspace.x[3] + acadoWorkspace.d[41]; -acadoVariables.x[46] += + acadoWorkspace.evGx[168]*acadoWorkspace.x[0] + acadoWorkspace.evGx[169]*acadoWorkspace.x[1] + acadoWorkspace.evGx[170]*acadoWorkspace.x[2] + acadoWorkspace.evGx[171]*acadoWorkspace.x[3] + acadoWorkspace.d[42]; -acadoVariables.x[47] += + acadoWorkspace.evGx[172]*acadoWorkspace.x[0] + acadoWorkspace.evGx[173]*acadoWorkspace.x[1] + acadoWorkspace.evGx[174]*acadoWorkspace.x[2] + acadoWorkspace.evGx[175]*acadoWorkspace.x[3] + acadoWorkspace.d[43]; -acadoVariables.x[48] += + acadoWorkspace.evGx[176]*acadoWorkspace.x[0] + acadoWorkspace.evGx[177]*acadoWorkspace.x[1] + acadoWorkspace.evGx[178]*acadoWorkspace.x[2] + acadoWorkspace.evGx[179]*acadoWorkspace.x[3] + acadoWorkspace.d[44]; -acadoVariables.x[49] += + acadoWorkspace.evGx[180]*acadoWorkspace.x[0] + acadoWorkspace.evGx[181]*acadoWorkspace.x[1] + acadoWorkspace.evGx[182]*acadoWorkspace.x[2] + acadoWorkspace.evGx[183]*acadoWorkspace.x[3] + acadoWorkspace.d[45]; -acadoVariables.x[50] += + acadoWorkspace.evGx[184]*acadoWorkspace.x[0] + acadoWorkspace.evGx[185]*acadoWorkspace.x[1] + acadoWorkspace.evGx[186]*acadoWorkspace.x[2] + acadoWorkspace.evGx[187]*acadoWorkspace.x[3] + acadoWorkspace.d[46]; -acadoVariables.x[51] += + acadoWorkspace.evGx[188]*acadoWorkspace.x[0] + acadoWorkspace.evGx[189]*acadoWorkspace.x[1] + acadoWorkspace.evGx[190]*acadoWorkspace.x[2] + acadoWorkspace.evGx[191]*acadoWorkspace.x[3] + acadoWorkspace.d[47]; -acadoVariables.x[52] += + acadoWorkspace.evGx[192]*acadoWorkspace.x[0] + acadoWorkspace.evGx[193]*acadoWorkspace.x[1] + acadoWorkspace.evGx[194]*acadoWorkspace.x[2] + acadoWorkspace.evGx[195]*acadoWorkspace.x[3] + acadoWorkspace.d[48]; -acadoVariables.x[53] += + acadoWorkspace.evGx[196]*acadoWorkspace.x[0] + acadoWorkspace.evGx[197]*acadoWorkspace.x[1] + acadoWorkspace.evGx[198]*acadoWorkspace.x[2] + acadoWorkspace.evGx[199]*acadoWorkspace.x[3] + acadoWorkspace.d[49]; -acadoVariables.x[54] += + acadoWorkspace.evGx[200]*acadoWorkspace.x[0] + acadoWorkspace.evGx[201]*acadoWorkspace.x[1] + acadoWorkspace.evGx[202]*acadoWorkspace.x[2] + acadoWorkspace.evGx[203]*acadoWorkspace.x[3] + acadoWorkspace.d[50]; -acadoVariables.x[55] += + acadoWorkspace.evGx[204]*acadoWorkspace.x[0] + acadoWorkspace.evGx[205]*acadoWorkspace.x[1] + acadoWorkspace.evGx[206]*acadoWorkspace.x[2] + acadoWorkspace.evGx[207]*acadoWorkspace.x[3] + acadoWorkspace.d[51]; -acadoVariables.x[56] += + acadoWorkspace.evGx[208]*acadoWorkspace.x[0] + acadoWorkspace.evGx[209]*acadoWorkspace.x[1] + acadoWorkspace.evGx[210]*acadoWorkspace.x[2] + acadoWorkspace.evGx[211]*acadoWorkspace.x[3] + acadoWorkspace.d[52]; -acadoVariables.x[57] += + acadoWorkspace.evGx[212]*acadoWorkspace.x[0] + acadoWorkspace.evGx[213]*acadoWorkspace.x[1] + acadoWorkspace.evGx[214]*acadoWorkspace.x[2] + acadoWorkspace.evGx[215]*acadoWorkspace.x[3] + acadoWorkspace.d[53]; -acadoVariables.x[58] += + acadoWorkspace.evGx[216]*acadoWorkspace.x[0] + acadoWorkspace.evGx[217]*acadoWorkspace.x[1] + acadoWorkspace.evGx[218]*acadoWorkspace.x[2] + acadoWorkspace.evGx[219]*acadoWorkspace.x[3] + acadoWorkspace.d[54]; -acadoVariables.x[59] += + acadoWorkspace.evGx[220]*acadoWorkspace.x[0] + acadoWorkspace.evGx[221]*acadoWorkspace.x[1] + acadoWorkspace.evGx[222]*acadoWorkspace.x[2] + acadoWorkspace.evGx[223]*acadoWorkspace.x[3] + acadoWorkspace.d[55]; -acadoVariables.x[60] += + acadoWorkspace.evGx[224]*acadoWorkspace.x[0] + acadoWorkspace.evGx[225]*acadoWorkspace.x[1] + acadoWorkspace.evGx[226]*acadoWorkspace.x[2] + acadoWorkspace.evGx[227]*acadoWorkspace.x[3] + acadoWorkspace.d[56]; -acadoVariables.x[61] += + acadoWorkspace.evGx[228]*acadoWorkspace.x[0] + acadoWorkspace.evGx[229]*acadoWorkspace.x[1] + acadoWorkspace.evGx[230]*acadoWorkspace.x[2] + acadoWorkspace.evGx[231]*acadoWorkspace.x[3] + acadoWorkspace.d[57]; -acadoVariables.x[62] += + acadoWorkspace.evGx[232]*acadoWorkspace.x[0] + acadoWorkspace.evGx[233]*acadoWorkspace.x[1] + acadoWorkspace.evGx[234]*acadoWorkspace.x[2] + acadoWorkspace.evGx[235]*acadoWorkspace.x[3] + acadoWorkspace.d[58]; -acadoVariables.x[63] += + acadoWorkspace.evGx[236]*acadoWorkspace.x[0] + acadoWorkspace.evGx[237]*acadoWorkspace.x[1] + acadoWorkspace.evGx[238]*acadoWorkspace.x[2] + acadoWorkspace.evGx[239]*acadoWorkspace.x[3] + acadoWorkspace.d[59]; -acadoVariables.x[64] += + acadoWorkspace.evGx[240]*acadoWorkspace.x[0] + acadoWorkspace.evGx[241]*acadoWorkspace.x[1] + acadoWorkspace.evGx[242]*acadoWorkspace.x[2] + acadoWorkspace.evGx[243]*acadoWorkspace.x[3] + acadoWorkspace.d[60]; -acadoVariables.x[65] += + acadoWorkspace.evGx[244]*acadoWorkspace.x[0] + acadoWorkspace.evGx[245]*acadoWorkspace.x[1] + acadoWorkspace.evGx[246]*acadoWorkspace.x[2] + acadoWorkspace.evGx[247]*acadoWorkspace.x[3] + acadoWorkspace.d[61]; -acadoVariables.x[66] += + acadoWorkspace.evGx[248]*acadoWorkspace.x[0] + acadoWorkspace.evGx[249]*acadoWorkspace.x[1] + acadoWorkspace.evGx[250]*acadoWorkspace.x[2] + acadoWorkspace.evGx[251]*acadoWorkspace.x[3] + acadoWorkspace.d[62]; -acadoVariables.x[67] += + acadoWorkspace.evGx[252]*acadoWorkspace.x[0] + acadoWorkspace.evGx[253]*acadoWorkspace.x[1] + acadoWorkspace.evGx[254]*acadoWorkspace.x[2] + acadoWorkspace.evGx[255]*acadoWorkspace.x[3] + acadoWorkspace.d[63]; -acadoVariables.x[68] += + acadoWorkspace.evGx[256]*acadoWorkspace.x[0] + acadoWorkspace.evGx[257]*acadoWorkspace.x[1] + acadoWorkspace.evGx[258]*acadoWorkspace.x[2] + acadoWorkspace.evGx[259]*acadoWorkspace.x[3] + acadoWorkspace.d[64]; -acadoVariables.x[69] += + acadoWorkspace.evGx[260]*acadoWorkspace.x[0] + acadoWorkspace.evGx[261]*acadoWorkspace.x[1] + acadoWorkspace.evGx[262]*acadoWorkspace.x[2] + acadoWorkspace.evGx[263]*acadoWorkspace.x[3] + acadoWorkspace.d[65]; -acadoVariables.x[70] += + acadoWorkspace.evGx[264]*acadoWorkspace.x[0] + acadoWorkspace.evGx[265]*acadoWorkspace.x[1] + acadoWorkspace.evGx[266]*acadoWorkspace.x[2] + acadoWorkspace.evGx[267]*acadoWorkspace.x[3] + acadoWorkspace.d[66]; -acadoVariables.x[71] += + acadoWorkspace.evGx[268]*acadoWorkspace.x[0] + acadoWorkspace.evGx[269]*acadoWorkspace.x[1] + acadoWorkspace.evGx[270]*acadoWorkspace.x[2] + acadoWorkspace.evGx[271]*acadoWorkspace.x[3] + acadoWorkspace.d[67]; -acadoVariables.x[72] += + acadoWorkspace.evGx[272]*acadoWorkspace.x[0] + acadoWorkspace.evGx[273]*acadoWorkspace.x[1] + acadoWorkspace.evGx[274]*acadoWorkspace.x[2] + acadoWorkspace.evGx[275]*acadoWorkspace.x[3] + acadoWorkspace.d[68]; -acadoVariables.x[73] += + acadoWorkspace.evGx[276]*acadoWorkspace.x[0] + acadoWorkspace.evGx[277]*acadoWorkspace.x[1] + acadoWorkspace.evGx[278]*acadoWorkspace.x[2] + acadoWorkspace.evGx[279]*acadoWorkspace.x[3] + acadoWorkspace.d[69]; -acadoVariables.x[74] += + acadoWorkspace.evGx[280]*acadoWorkspace.x[0] + acadoWorkspace.evGx[281]*acadoWorkspace.x[1] + acadoWorkspace.evGx[282]*acadoWorkspace.x[2] + acadoWorkspace.evGx[283]*acadoWorkspace.x[3] + acadoWorkspace.d[70]; -acadoVariables.x[75] += + acadoWorkspace.evGx[284]*acadoWorkspace.x[0] + acadoWorkspace.evGx[285]*acadoWorkspace.x[1] + acadoWorkspace.evGx[286]*acadoWorkspace.x[2] + acadoWorkspace.evGx[287]*acadoWorkspace.x[3] + acadoWorkspace.d[71]; -acadoVariables.x[76] += + acadoWorkspace.evGx[288]*acadoWorkspace.x[0] + acadoWorkspace.evGx[289]*acadoWorkspace.x[1] + acadoWorkspace.evGx[290]*acadoWorkspace.x[2] + acadoWorkspace.evGx[291]*acadoWorkspace.x[3] + acadoWorkspace.d[72]; -acadoVariables.x[77] += + acadoWorkspace.evGx[292]*acadoWorkspace.x[0] + acadoWorkspace.evGx[293]*acadoWorkspace.x[1] + acadoWorkspace.evGx[294]*acadoWorkspace.x[2] + acadoWorkspace.evGx[295]*acadoWorkspace.x[3] + acadoWorkspace.d[73]; -acadoVariables.x[78] += + acadoWorkspace.evGx[296]*acadoWorkspace.x[0] + acadoWorkspace.evGx[297]*acadoWorkspace.x[1] + acadoWorkspace.evGx[298]*acadoWorkspace.x[2] + acadoWorkspace.evGx[299]*acadoWorkspace.x[3] + acadoWorkspace.d[74]; -acadoVariables.x[79] += + acadoWorkspace.evGx[300]*acadoWorkspace.x[0] + acadoWorkspace.evGx[301]*acadoWorkspace.x[1] + acadoWorkspace.evGx[302]*acadoWorkspace.x[2] + acadoWorkspace.evGx[303]*acadoWorkspace.x[3] + acadoWorkspace.d[75]; -acadoVariables.x[80] += + acadoWorkspace.evGx[304]*acadoWorkspace.x[0] + acadoWorkspace.evGx[305]*acadoWorkspace.x[1] + acadoWorkspace.evGx[306]*acadoWorkspace.x[2] + acadoWorkspace.evGx[307]*acadoWorkspace.x[3] + acadoWorkspace.d[76]; -acadoVariables.x[81] += + acadoWorkspace.evGx[308]*acadoWorkspace.x[0] + acadoWorkspace.evGx[309]*acadoWorkspace.x[1] + acadoWorkspace.evGx[310]*acadoWorkspace.x[2] + acadoWorkspace.evGx[311]*acadoWorkspace.x[3] + acadoWorkspace.d[77]; -acadoVariables.x[82] += + acadoWorkspace.evGx[312]*acadoWorkspace.x[0] + acadoWorkspace.evGx[313]*acadoWorkspace.x[1] + acadoWorkspace.evGx[314]*acadoWorkspace.x[2] + acadoWorkspace.evGx[315]*acadoWorkspace.x[3] + acadoWorkspace.d[78]; -acadoVariables.x[83] += + acadoWorkspace.evGx[316]*acadoWorkspace.x[0] + acadoWorkspace.evGx[317]*acadoWorkspace.x[1] + acadoWorkspace.evGx[318]*acadoWorkspace.x[2] + acadoWorkspace.evGx[319]*acadoWorkspace.x[3] + acadoWorkspace.d[79]; - -acado_multEDu( acadoWorkspace.E, &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 4 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 8 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 8 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 12 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 12 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 12 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 16 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 16 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 16 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 16 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 20 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 20 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 20 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 20 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 20 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 24 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 24 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 24 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 24 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 24 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 24 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 28 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 28 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 28 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 28 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 28 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 28 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 28 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 32 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 36 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 40 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 44 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 48 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 52 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 56 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 60 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 64 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 68 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 72 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 76 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 80 ]) ); -acado_multEDu( &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.x[ 23 ]), &(acadoVariables.x[ 80 ]) ); -} - -int acado_preparationStep( ) -{ -int ret; - -ret = acado_modelSimulation(); -acado_evaluateObjective( ); -acado_condensePrep( ); -return ret; -} - -int acado_feedbackStep( ) -{ -int tmp; - -acado_condenseFdb( ); - -tmp = acado_solve( ); - -acado_expand( ); -return tmp; -} - -int acado_initializeSolver( ) -{ -int ret; - -/* This is a function which must be called once before any other function call! */ - - -ret = 0; - -memset(&acadoWorkspace, 0, sizeof( acadoWorkspace )); -return ret; -} - -void acado_initializeNodesByForwardSimulation( ) -{ -int index; -for (index = 0; index < 20; ++index) -{ -acadoWorkspace.state[0] = acadoVariables.x[index * 4]; -acadoWorkspace.state[1] = acadoVariables.x[index * 4 + 1]; -acadoWorkspace.state[2] = acadoVariables.x[index * 4 + 2]; -acadoWorkspace.state[3] = acadoVariables.x[index * 4 + 3]; -acadoWorkspace.state[24] = acadoVariables.u[index]; -acadoWorkspace.state[25] = acadoVariables.od[index * 12]; -acadoWorkspace.state[26] = acadoVariables.od[index * 12 + 1]; -acadoWorkspace.state[27] = acadoVariables.od[index * 12 + 2]; -acadoWorkspace.state[28] = acadoVariables.od[index * 12 + 3]; -acadoWorkspace.state[29] = acadoVariables.od[index * 12 + 4]; -acadoWorkspace.state[30] = acadoVariables.od[index * 12 + 5]; -acadoWorkspace.state[31] = acadoVariables.od[index * 12 + 6]; -acadoWorkspace.state[32] = acadoVariables.od[index * 12 + 7]; -acadoWorkspace.state[33] = acadoVariables.od[index * 12 + 8]; -acadoWorkspace.state[34] = acadoVariables.od[index * 12 + 9]; -acadoWorkspace.state[35] = acadoVariables.od[index * 12 + 10]; -acadoWorkspace.state[36] = acadoVariables.od[index * 12 + 11]; - -acado_integrate(acadoWorkspace.state, index == 0, index); - -acadoVariables.x[index * 4 + 4] = acadoWorkspace.state[0]; -acadoVariables.x[index * 4 + 5] = acadoWorkspace.state[1]; -acadoVariables.x[index * 4 + 6] = acadoWorkspace.state[2]; -acadoVariables.x[index * 4 + 7] = acadoWorkspace.state[3]; -} -} - -void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ) -{ -int index; -for (index = 0; index < 20; ++index) -{ -acadoVariables.x[index * 4] = acadoVariables.x[index * 4 + 4]; -acadoVariables.x[index * 4 + 1] = acadoVariables.x[index * 4 + 5]; -acadoVariables.x[index * 4 + 2] = acadoVariables.x[index * 4 + 6]; -acadoVariables.x[index * 4 + 3] = acadoVariables.x[index * 4 + 7]; -} - -if (strategy == 1 && xEnd != 0) -{ -acadoVariables.x[80] = xEnd[0]; -acadoVariables.x[81] = xEnd[1]; -acadoVariables.x[82] = xEnd[2]; -acadoVariables.x[83] = xEnd[3]; -} -else if (strategy == 2) -{ -acadoWorkspace.state[0] = acadoVariables.x[80]; -acadoWorkspace.state[1] = acadoVariables.x[81]; -acadoWorkspace.state[2] = acadoVariables.x[82]; -acadoWorkspace.state[3] = acadoVariables.x[83]; -if (uEnd != 0) -{ -acadoWorkspace.state[24] = uEnd[0]; -} -else -{ -acadoWorkspace.state[24] = acadoVariables.u[19]; -} -acadoWorkspace.state[25] = acadoVariables.od[240]; -acadoWorkspace.state[26] = acadoVariables.od[241]; -acadoWorkspace.state[27] = acadoVariables.od[242]; -acadoWorkspace.state[28] = acadoVariables.od[243]; -acadoWorkspace.state[29] = acadoVariables.od[244]; -acadoWorkspace.state[30] = acadoVariables.od[245]; -acadoWorkspace.state[31] = acadoVariables.od[246]; -acadoWorkspace.state[32] = acadoVariables.od[247]; -acadoWorkspace.state[33] = acadoVariables.od[248]; -acadoWorkspace.state[34] = acadoVariables.od[249]; -acadoWorkspace.state[35] = acadoVariables.od[250]; -acadoWorkspace.state[36] = acadoVariables.od[251]; - -acado_integrate(acadoWorkspace.state, 1, 19); - -acadoVariables.x[80] = acadoWorkspace.state[0]; -acadoVariables.x[81] = acadoWorkspace.state[1]; -acadoVariables.x[82] = acadoWorkspace.state[2]; -acadoVariables.x[83] = acadoWorkspace.state[3]; -} -} - -void acado_shiftControls( real_t* const uEnd ) -{ -int index; -for (index = 0; index < 19; ++index) -{ -acadoVariables.u[index] = acadoVariables.u[index + 1]; -} - -if (uEnd != 0) -{ -acadoVariables.u[19] = uEnd[0]; -} -} - -real_t acado_getKKT( ) -{ -real_t kkt; - -int index; -real_t prd; - -kkt = + acadoWorkspace.g[0]*acadoWorkspace.x[0] + acadoWorkspace.g[1]*acadoWorkspace.x[1] + acadoWorkspace.g[2]*acadoWorkspace.x[2] + acadoWorkspace.g[3]*acadoWorkspace.x[3] + acadoWorkspace.g[4]*acadoWorkspace.x[4] + acadoWorkspace.g[5]*acadoWorkspace.x[5] + acadoWorkspace.g[6]*acadoWorkspace.x[6] + acadoWorkspace.g[7]*acadoWorkspace.x[7] + acadoWorkspace.g[8]*acadoWorkspace.x[8] + acadoWorkspace.g[9]*acadoWorkspace.x[9] + acadoWorkspace.g[10]*acadoWorkspace.x[10] + acadoWorkspace.g[11]*acadoWorkspace.x[11] + acadoWorkspace.g[12]*acadoWorkspace.x[12] + acadoWorkspace.g[13]*acadoWorkspace.x[13] + acadoWorkspace.g[14]*acadoWorkspace.x[14] + acadoWorkspace.g[15]*acadoWorkspace.x[15] + acadoWorkspace.g[16]*acadoWorkspace.x[16] + acadoWorkspace.g[17]*acadoWorkspace.x[17] + acadoWorkspace.g[18]*acadoWorkspace.x[18] + acadoWorkspace.g[19]*acadoWorkspace.x[19] + acadoWorkspace.g[20]*acadoWorkspace.x[20] + acadoWorkspace.g[21]*acadoWorkspace.x[21] + acadoWorkspace.g[22]*acadoWorkspace.x[22] + acadoWorkspace.g[23]*acadoWorkspace.x[23]; -kkt = fabs( kkt ); -for (index = 0; index < 24; ++index) -{ -prd = acadoWorkspace.y[index]; -if (prd > 1e-12) -kkt += fabs(acadoWorkspace.lb[index] * prd); -else if (prd < -1e-12) -kkt += fabs(acadoWorkspace.ub[index] * prd); -} -return kkt; -} - -real_t acado_getObjective( ) -{ -real_t objVal; - -int lRun1; -/** Row vector of size: 5 */ -real_t tmpDy[ 5 ]; - -/** Row vector of size: 4 */ -real_t tmpDyN[ 4 ]; - -for (lRun1 = 0; lRun1 < 20; ++lRun1) -{ -acadoWorkspace.objValueIn[0] = acadoVariables.x[lRun1 * 4]; -acadoWorkspace.objValueIn[1] = acadoVariables.x[lRun1 * 4 + 1]; -acadoWorkspace.objValueIn[2] = acadoVariables.x[lRun1 * 4 + 2]; -acadoWorkspace.objValueIn[3] = acadoVariables.x[lRun1 * 4 + 3]; -acadoWorkspace.objValueIn[4] = acadoVariables.u[lRun1]; -acadoWorkspace.objValueIn[5] = acadoVariables.od[lRun1 * 12]; -acadoWorkspace.objValueIn[6] = acadoVariables.od[lRun1 * 12 + 1]; -acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1 * 12 + 2]; -acadoWorkspace.objValueIn[8] = acadoVariables.od[lRun1 * 12 + 3]; -acadoWorkspace.objValueIn[9] = acadoVariables.od[lRun1 * 12 + 4]; -acadoWorkspace.objValueIn[10] = acadoVariables.od[lRun1 * 12 + 5]; -acadoWorkspace.objValueIn[11] = acadoVariables.od[lRun1 * 12 + 6]; -acadoWorkspace.objValueIn[12] = acadoVariables.od[lRun1 * 12 + 7]; -acadoWorkspace.objValueIn[13] = acadoVariables.od[lRun1 * 12 + 8]; -acadoWorkspace.objValueIn[14] = acadoVariables.od[lRun1 * 12 + 9]; -acadoWorkspace.objValueIn[15] = acadoVariables.od[lRun1 * 12 + 10]; -acadoWorkspace.objValueIn[16] = acadoVariables.od[lRun1 * 12 + 11]; - -acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); -acadoWorkspace.Dy[lRun1 * 5] = acadoWorkspace.objValueOut[0] - acadoVariables.y[lRun1 * 5]; -acadoWorkspace.Dy[lRun1 * 5 + 1] = acadoWorkspace.objValueOut[1] - acadoVariables.y[lRun1 * 5 + 1]; -acadoWorkspace.Dy[lRun1 * 5 + 2] = acadoWorkspace.objValueOut[2] - acadoVariables.y[lRun1 * 5 + 2]; -acadoWorkspace.Dy[lRun1 * 5 + 3] = acadoWorkspace.objValueOut[3] - acadoVariables.y[lRun1 * 5 + 3]; -acadoWorkspace.Dy[lRun1 * 5 + 4] = acadoWorkspace.objValueOut[4] - acadoVariables.y[lRun1 * 5 + 4]; -} -acadoWorkspace.objValueIn[0] = acadoVariables.x[80]; -acadoWorkspace.objValueIn[1] = acadoVariables.x[81]; -acadoWorkspace.objValueIn[2] = acadoVariables.x[82]; -acadoWorkspace.objValueIn[3] = acadoVariables.x[83]; -acadoWorkspace.objValueIn[4] = acadoVariables.od[240]; -acadoWorkspace.objValueIn[5] = acadoVariables.od[241]; -acadoWorkspace.objValueIn[6] = acadoVariables.od[242]; -acadoWorkspace.objValueIn[7] = acadoVariables.od[243]; -acadoWorkspace.objValueIn[8] = acadoVariables.od[244]; -acadoWorkspace.objValueIn[9] = acadoVariables.od[245]; -acadoWorkspace.objValueIn[10] = acadoVariables.od[246]; -acadoWorkspace.objValueIn[11] = acadoVariables.od[247]; -acadoWorkspace.objValueIn[12] = acadoVariables.od[248]; -acadoWorkspace.objValueIn[13] = acadoVariables.od[249]; -acadoWorkspace.objValueIn[14] = acadoVariables.od[250]; -acadoWorkspace.objValueIn[15] = acadoVariables.od[251]; -acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); -acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0] - acadoVariables.yN[0]; -acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1] - acadoVariables.yN[1]; -acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2] - acadoVariables.yN[2]; -acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3] - acadoVariables.yN[3]; -objVal = 0.0000000000000000e+00; -for (lRun1 = 0; lRun1 < 20; ++lRun1) -{ -tmpDy[0] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 5] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 10] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 15] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 20]; -tmpDy[1] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 1] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 6] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 11] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 16] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 21]; -tmpDy[2] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 2] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 7] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 12] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 17] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 22]; -tmpDy[3] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 3] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 8] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 13] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 18] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 23]; -tmpDy[4] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 4] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 9] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 14] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 19] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 24]; -objVal += + acadoWorkspace.Dy[lRun1 * 5]*tmpDy[0] + acadoWorkspace.Dy[lRun1 * 5 + 1]*tmpDy[1] + acadoWorkspace.Dy[lRun1 * 5 + 2]*tmpDy[2] + acadoWorkspace.Dy[lRun1 * 5 + 3]*tmpDy[3] + acadoWorkspace.Dy[lRun1 * 5 + 4]*tmpDy[4]; -} - -tmpDyN[0] = + acadoWorkspace.DyN[0]*acadoVariables.WN[0] + acadoWorkspace.DyN[1]*acadoVariables.WN[4] + acadoWorkspace.DyN[2]*acadoVariables.WN[8] + acadoWorkspace.DyN[3]*acadoVariables.WN[12]; -tmpDyN[1] = + acadoWorkspace.DyN[0]*acadoVariables.WN[1] + acadoWorkspace.DyN[1]*acadoVariables.WN[5] + acadoWorkspace.DyN[2]*acadoVariables.WN[9] + acadoWorkspace.DyN[3]*acadoVariables.WN[13]; -tmpDyN[2] = + acadoWorkspace.DyN[0]*acadoVariables.WN[2] + acadoWorkspace.DyN[1]*acadoVariables.WN[6] + acadoWorkspace.DyN[2]*acadoVariables.WN[10] + acadoWorkspace.DyN[3]*acadoVariables.WN[14]; -tmpDyN[3] = + acadoWorkspace.DyN[0]*acadoVariables.WN[3] + acadoWorkspace.DyN[1]*acadoVariables.WN[7] + acadoWorkspace.DyN[2]*acadoVariables.WN[11] + acadoWorkspace.DyN[3]*acadoVariables.WN[15]; -objVal += + acadoWorkspace.DyN[0]*tmpDyN[0] + acadoWorkspace.DyN[1]*tmpDyN[1] + acadoWorkspace.DyN[2]*tmpDyN[2] + acadoWorkspace.DyN[3]*tmpDyN[3]; - -objVal *= 0.5; -return objVal; -} - diff --git a/selfdrive/controls/lib/longitudinal_mpc_model/libmpc_py.py b/selfdrive/controls/lib/longitudinal_mpc_model/libmpc_py.py deleted file mode 100644 index a25dbb66d..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_model/libmpc_py.py +++ /dev/null @@ -1,32 +0,0 @@ -import os - -from cffi import FFI -from common.ffi_wrapper import suffix - -mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__))) -libmpc_fn = os.path.join(mpc_dir, "libmpc"+suffix()) - -ffi = FFI() -ffi.cdef(""" - -typedef struct { -double x_ego, v_ego, a_ego; -} state_t; - - -typedef struct { -double x_ego[21]; -double v_ego[21]; -double a_ego[21]; -double t[21]; -double j_ego[20]; -double cost; -} log_t; - - -void init(double xCost, double vCost, double aCost, double accelCost, double jerkCost); -void init_with_simulation(double v_ego); -int run_mpc(state_t * x0, log_t * solution, double x_poly[4], double v_poly[4], double a_poly[4]); -""") - -libmpc = ffi.dlopen(libmpc_fn) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 2f18a753c..643cefd7a 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -1,46 +1,34 @@ #!/usr/bin/env python3 import math import numpy as np -from common.params import Params from common.numpy_fast import interp import cereal.messaging as messaging +from cereal import log +from common.realtime import DT_MDL from common.realtime import sec_since_boot -from selfdrive.swaglog import cloudlog +from selfdrive.modeld.constants import T_IDXS from selfdrive.config import Conversions as CV -from selfdrive.controls.lib.speed_smoother import speed_smoother -from selfdrive.controls.lib.longcontrol import LongCtrlState from selfdrive.controls.lib.fcw import FCWChecker +from selfdrive.controls.lib.longcontrol import LongCtrlState +from selfdrive.controls.lib.lead_mpc import LeadMpc from selfdrive.controls.lib.long_mpc import LongitudinalMpc -from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX +from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N +from selfdrive.swaglog import cloudlog LON_MPC_STEP = 0.2 # first step is 0.2s AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted - -# lookup tables VS speed to determine min and max accels in cruise -# make sure these accelerations are smaller than mpc limits -_A_CRUISE_MIN_V = [-1.0, -.8, -.67, -.5, -.30] -_A_CRUISE_MIN_BP = [ 0., 5., 10., 20., 40.] - -# need fast accel at very low speed for stop and go -# make sure these accelerations are smaller than mpc limits -_A_CRUISE_MAX_V = [1.2, 1.2, 0.65, .4] -_A_CRUISE_MAX_V_FOLLOWING = [1.6, 1.6, 0.65, .4] -_A_CRUISE_MAX_BP = [0., 6.4, 22.5, 40.] +A_CRUISE_MIN = -1.2 +A_CRUISE_MAX_VALS = [1.2, 1.2, 0.8, 0.6] +A_CRUISE_MAX_BP = [0., 15., 25., 40.] # Lookup table for turns _A_TOTAL_MAX_V = [1.7, 3.2] _A_TOTAL_MAX_BP = [20., 40.] -def calc_cruise_accel_limits(v_ego, following): - a_cruise_min = interp(v_ego, _A_CRUISE_MIN_BP, _A_CRUISE_MIN_V) - - if following: - a_cruise_max = interp(v_ego, _A_CRUISE_MAX_BP, _A_CRUISE_MAX_V_FOLLOWING) - else: - a_cruise_max = interp(v_ego, _A_CRUISE_MAX_BP, _A_CRUISE_MAX_V) - return np.vstack([a_cruise_min, a_cruise_max]) +def get_max_accel(v_ego): + return interp(v_ego, A_CRUISE_MAX_BP, A_CRUISE_MAX_VALS) def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): @@ -59,159 +47,104 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): class Planner(): def __init__(self, CP): self.CP = CP - - self.mpc1 = LongitudinalMpc(1) - self.mpc2 = LongitudinalMpc(2) - - self.v_acc_start = 0.0 - self.a_acc_start = 0.0 - self.v_acc_next = 0.0 - self.a_acc_next = 0.0 - - self.v_acc = 0.0 - self.v_acc_future = 0.0 - self.a_acc = 0.0 - self.v_cruise = 0.0 - self.a_cruise = 0.0 - - self.longitudinalPlanSource = 'cruise' - self.fcw_checker = FCWChecker() - self.path_x = np.arange(192) + self.mpcs = {} + self.mpcs['lead0'] = LeadMpc(0) + self.mpcs['lead1'] = LeadMpc(1) + self.mpcs['cruise'] = LongitudinalMpc() self.fcw = False + self.fcw_checker = FCWChecker() - self.params = Params() - self.first_loop = True + self.v_desired = 0.0 + self.a_desired = 0.0 + self.longitudinalPlanSource = 'cruise' + self.alpha = np.exp(-DT_MDL/2.0) + self.lead_0 = log.ModelDataV2.LeadDataV3.new_message() + self.lead_1 = log.ModelDataV2.LeadDataV3.new_message() - def choose_solution(self, v_cruise_setpoint, enabled): - if enabled: - solutions = {'cruise': self.v_cruise} - if self.mpc1.prev_lead_status: - solutions['mpc1'] = self.mpc1.v_mpc - if self.mpc2.prev_lead_status: - solutions['mpc2'] = self.mpc2.v_mpc + self.v_desired_trajectory = np.zeros(CONTROL_N) + self.a_desired_trajectory = np.zeros(CONTROL_N) - slowest = min(solutions, key=solutions.get) - - self.longitudinalPlanSource = slowest - # Choose lowest of MPC and cruise - if slowest == 'mpc1': - self.v_acc = self.mpc1.v_mpc - self.a_acc = self.mpc1.a_mpc - elif slowest == 'mpc2': - self.v_acc = self.mpc2.v_mpc - self.a_acc = self.mpc2.a_mpc - elif slowest == 'cruise': - self.v_acc = self.v_cruise - self.a_acc = self.a_cruise - - self.v_acc_future = min([self.mpc1.v_mpc_future, self.mpc2.v_mpc_future, v_cruise_setpoint]) def update(self, sm, CP): - """Gets called when new radarState is available""" cur_time = sec_since_boot() v_ego = sm['carState'].vEgo + a_ego = sm['carState'].aEgo + + v_cruise_kph = sm['controlsState'].vCruise + v_cruise_kph = min(v_cruise_kph, V_CRUISE_MAX) + v_cruise = v_cruise_kph * CV.KPH_TO_MS long_control_state = sm['controlsState'].longControlState - v_cruise_kph = sm['controlsState'].vCruise force_slow_decel = sm['controlsState'].forceDecel - v_cruise_kph = min(v_cruise_kph, V_CRUISE_MAX) - v_cruise_setpoint = v_cruise_kph * CV.KPH_TO_MS - - lead_1 = sm['radarState'].leadOne - lead_2 = sm['radarState'].leadTwo + self.lead_0 = sm['radarState'].leadOne + self.lead_1 = sm['radarState'].leadTwo enabled = (long_control_state == LongCtrlState.pid) or (long_control_state == LongCtrlState.stopping) - following = lead_1.status and lead_1.dRel < 45.0 and lead_1.vLeadK > v_ego and lead_1.aLeadK > 0.0 + if not enabled or sm['carState'].gasPressed: + self.v_desired = v_ego + self.a_desired = a_ego - self.v_acc_start = self.v_acc_next - self.a_acc_start = self.a_acc_next + # Prevent divergence, smooth in current v_ego + self.v_desired = self.alpha * self.v_desired + (1 - self.alpha) * v_ego + self.v_desired = max(0.0, self.v_desired) - # Calculate speed for normal cruise control - if enabled and not self.first_loop and not sm['carState'].gasPressed: - accel_limits = [float(x) for x in calc_cruise_accel_limits(v_ego, following)] - jerk_limits = [min(-0.1, accel_limits[0]), max(0.1, accel_limits[1])] # TODO: make a separate lookup for jerk tuning - accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP) + accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)] + accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP) + if force_slow_decel: + # if required so, force a smooth deceleration + accel_limits_turns[1] = min(accel_limits_turns[1], AWARENESS_DECEL) + accel_limits_turns[0] = min(accel_limits_turns[0], accel_limits_turns[1]) + # clip limits, cannot init MPC outside of bounds + accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired) + accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired) + self.mpcs['cruise'].set_accel_limits(accel_limits_turns[0], accel_limits_turns[1]) - if force_slow_decel: - # if required so, force a smooth deceleration - accel_limits_turns[1] = min(accel_limits_turns[1], AWARENESS_DECEL) - accel_limits_turns[0] = min(accel_limits_turns[0], accel_limits_turns[1]) - - self.v_cruise, self.a_cruise = speed_smoother(self.v_acc_start, self.a_acc_start, - v_cruise_setpoint, - accel_limits_turns[1], accel_limits_turns[0], - jerk_limits[1], jerk_limits[0], - LON_MPC_STEP) - - # cruise speed can't be negative even is user is distracted - self.v_cruise = max(self.v_cruise, 0.) - else: - starting = long_control_state == LongCtrlState.starting - a_ego = min(sm['carState'].aEgo, 0.0) - reset_speed = self.CP.minSpeedCan if starting else v_ego - reset_accel = self.CP.startAccel if starting else a_ego - self.v_acc = reset_speed - self.a_acc = reset_accel - self.v_acc_start = reset_speed - self.a_acc_start = reset_accel - self.v_cruise = reset_speed - self.a_cruise = reset_accel - - self.mpc1.set_cur_state(self.v_acc_start, self.a_acc_start) - self.mpc2.set_cur_state(self.v_acc_start, self.a_acc_start) - - self.mpc1.update(sm['carState'], lead_1) - self.mpc2.update(sm['carState'], lead_2) - - self.choose_solution(v_cruise_setpoint, enabled) + next_a = np.inf + for key in self.mpcs: + self.mpcs[key].set_cur_state(self.v_desired, self.a_desired) + self.mpcs[key].update(sm['carState'], sm['radarState'], v_cruise) + if self.mpcs[key].status and self.mpcs[key].a_solution[5] < next_a: + self.longitudinalPlanSource = key + self.v_desired_trajectory = self.mpcs[key].v_solution[:CONTROL_N] + self.a_desired_trajectory = self.mpcs[key].a_solution[:CONTROL_N] + self.j_desired_trajectory = self.mpcs[key].j_solution[:CONTROL_N] + next_a = self.mpcs[key].a_solution[5] # determine fcw - if self.mpc1.new_lead: + if self.mpcs['lead0'].new_lead: self.fcw_checker.reset_lead(cur_time) - blinkers = sm['carState'].leftBlinker or sm['carState'].rightBlinker - self.fcw = self.fcw_checker.update(self.mpc1.mpc_solution, cur_time, + self.fcw = self.fcw_checker.update(self.mpcs['lead0'].mpc_solution, cur_time, sm['controlsState'].active, v_ego, sm['carState'].aEgo, - lead_1.dRel, lead_1.vLead, lead_1.aLeadK, - lead_1.yRel, lead_1.vLat, - lead_1.fcw, blinkers) and not sm['carState'].brakePressed + self.lead_1.dRel, self.lead_1.vLead, self.lead_1.aLeadK, + self.lead_1.yRel, self.lead_1.vLat, + self.lead_1.fcw, blinkers) and not sm['carState'].brakePressed if self.fcw: cloudlog.info("FCW triggered %s", self.fcw_checker.counters) # Interpolate 0.05 seconds and save as starting point for next iteration - a_acc_sol = self.a_acc_start + (CP.radarTimeStep / LON_MPC_STEP) * (self.a_acc - self.a_acc_start) - v_acc_sol = self.v_acc_start + CP.radarTimeStep * (a_acc_sol + self.a_acc_start) / 2.0 - self.v_acc_next = v_acc_sol - self.a_acc_next = a_acc_sol - - self.first_loop = False + a_prev = self.a_desired + self.a_desired = float(interp(DT_MDL, T_IDXS[:CONTROL_N], self.a_desired_trajectory)) + self.v_desired = self.v_desired + DT_MDL * (self.a_desired + a_prev)/2.0 def publish(self, sm, pm): - self.mpc1.publish(pm) - self.mpc2.publish(pm) - plan_send = messaging.new_message('longitudinalPlan') - plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'radarState']) + plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState']) longitudinalPlan = plan_send.longitudinalPlan - longitudinalPlan.mdMonoTime = sm.logMonoTime['modelV2'] - longitudinalPlan.radarStateMonoTime = sm.logMonoTime['radarState'] + longitudinalPlan.modelMonoTime = sm.logMonoTime['modelV2'] + longitudinalPlan.processingDelay = (plan_send.logMonoTime / 1e9) - sm.logMonoTime['modelV2'] - longitudinalPlan.vCruise = float(self.v_cruise) - longitudinalPlan.aCruise = float(self.a_cruise) - longitudinalPlan.vStart = float(self.v_acc_start) - longitudinalPlan.aStart = float(self.a_acc_start) - longitudinalPlan.vTarget = float(self.v_acc) - longitudinalPlan.aTarget = float(self.a_acc) - longitudinalPlan.vTargetFuture = float(self.v_acc_future) - longitudinalPlan.hasLead = self.mpc1.prev_lead_status + longitudinalPlan.speeds = [float(x) for x in self.v_desired_trajectory] + longitudinalPlan.accels = [float(x) for x in self.a_desired_trajectory] + longitudinalPlan.jerks = [float(x) for x in self.j_desired_trajectory] + + longitudinalPlan.hasLead = self.mpcs['lead0'].status longitudinalPlan.longitudinalPlanSource = self.longitudinalPlanSource longitudinalPlan.fcw = self.fcw - longitudinalPlan.processingDelay = (plan_send.logMonoTime / 1e9) - sm.rcv_time['radarState'] - pm.send('longitudinalPlan', plan_send) diff --git a/selfdrive/controls/lib/speed_smoother.py b/selfdrive/controls/lib/speed_smoother.py deleted file mode 100644 index 431822dd9..000000000 --- a/selfdrive/controls/lib/speed_smoother.py +++ /dev/null @@ -1,99 +0,0 @@ -import numpy as np - - -def get_delta_out_limits(aEgo, aMax, aMin, jMax, jMin): - - tDelta = 0. - if aEgo > aMax: - tDelta = (aMax - aEgo) / jMin - elif aEgo < aMin: - tDelta = (aMin - aEgo) / jMax - - return tDelta - - -def speed_smoother(vEgo, aEgo, vT, aMax, aMin, jMax, jMin, ts): - - dV = vT - vEgo - - # recover quickly if dV is positive and aEgo is negative or viceversa - if dV > 0. and aEgo < 0.: - jMax *= 3. - elif dV < 0. and aEgo > 0.: - jMin *= 3. - - tDelta = get_delta_out_limits(aEgo, aMax, aMin, jMax, jMin) - - if (ts <= tDelta): - if (aEgo < aMin): - vEgo += ts * aEgo + 0.5 * ts**2 * jMax - aEgo += ts * jMax - return vEgo, aEgo - elif (aEgo > aMax): - vEgo += ts * aEgo + 0.5 * ts**2 * jMin - aEgo += ts * jMin - return vEgo, aEgo - - if aEgo > aMax: - dV -= 0.5 * (aMax**2 - aEgo**2) / jMin - vEgo += 0.5 * (aMax**2 - aEgo**2) / jMin - aEgo += tDelta * jMin - elif aEgo < aMin: - dV -= 0.5 * (aMin**2 - aEgo**2) / jMax - vEgo += 0.5 * (aMin**2 - aEgo**2) / jMax - aEgo += tDelta * jMax - - ts -= tDelta - - jLim = jMin if aEgo >= 0 else jMax - # if we reduce the accel to zero immediately, how much delta speed we generate? - dv_min_shift = - 0.5 * aEgo**2 / jLim - - # flip signs so we can consider only one case - flipped = False - if dV < dv_min_shift: - flipped = True - dV *= -1 - vEgo *= -1 - aEgo *= -1 - aMax = -aMin - jMaxcopy = -jMin - jMin = -jMax - jMax = jMaxcopy - - # small addition needed to avoid numerical issues with sqrt of ~zero - aPeak = np.sqrt((0.5 * aEgo**2 / jMax + dV + 1e-9) / (0.5 / jMax - 0.5 / jMin)) - - if aPeak > aMax: - aPeak = aMax - t1 = (aPeak - aEgo) / jMax - if aPeak <= 0: # there is no solution, so stop after t1 - t2 = t1 + ts + 1e-9 - t3 = t2 - else: - vChange = dV - 0.5 * (aPeak**2 - aEgo**2) / jMax + 0.5 * aPeak**2 / jMin - if vChange < aPeak * ts: - t2 = t1 + vChange / aPeak - else: - t2 = t1 + ts - t3 = t2 - aPeak / jMin - else: - t1 = (aPeak - aEgo) / jMax - t2 = t1 - t3 = t2 - aPeak / jMin - - dt1 = min(ts, t1) - dt2 = max(min(ts, t2) - t1, 0.) - dt3 = max(min(ts, t3) - t2, 0.) - - if ts > t3: - vEgo += dV - aEgo = 0. - else: - vEgo += aEgo * dt1 + 0.5 * dt1**2 * jMax + aPeak * dt2 + aPeak * dt3 + 0.5 * dt3**2 * jMin - aEgo += jMax * dt1 + dt3 * jMin - - vEgo *= -1 if flipped else 1 - aEgo *= -1 if flipped else 1 - - return float(vEgo), float(aEgo) diff --git a/selfdrive/debug/can_print_changes.py b/selfdrive/debug/can_print_changes.py new file mode 100755 index 000000000..4fa775ac1 --- /dev/null +++ b/selfdrive/debug/can_print_changes.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python3 +import binascii +import sys +from collections import defaultdict + +import cereal.messaging as messaging +from common.realtime import sec_since_boot + + +def can_printer(bus=0): + """Collects messages and prints when a new bit transition is observed. + This is very useful to find signals based on user triggered actions, such as blinkers and seatbelt. + Leave the script running until no new transitions are seen, then perform the action.""" + logcan = messaging.sub_sock('can') + + low_to_high = defaultdict(int) + high_to_low = defaultdict(int) + + while 1: + can_recv = messaging.drain_sock(logcan, wait_for_one=True) + for x in can_recv: + for y in x.can: + if y.src == bus: + i = int.from_bytes(y.dat, byteorder='big') + + l_h = low_to_high[y.address] + h_l = high_to_low[y.address] + + change = None + if (i | l_h) != l_h: + low_to_high[y.address] = i | l_h + change = "+" + + if (~i | h_l) != h_l: + high_to_low[y.address] = ~i | h_l + change = "-" + + if change: + print(f"{sec_since_boot():.2f}\t{hex(y.address)} ({y.address})\t{change}{binascii.hexlify(y.dat)}") + + +if __name__ == "__main__": + if len(sys.argv) > 1: + can_printer(int(sys.argv[1])) + else: + can_printer() diff --git a/selfdrive/debug/check_freq.py b/selfdrive/debug/check_freq.py index fd4f510c2..300b3ea1f 100755 --- a/selfdrive/debug/check_freq.py +++ b/selfdrive/debug/check_freq.py @@ -20,6 +20,7 @@ if __name__ == "__main__": sockets = {} rcv_times = defaultdict(lambda: deque(maxlen=100)) + valids = defaultdict(lambda: deque(maxlen=100)) t = sec_since_boot() for name in socket_names: @@ -34,12 +35,13 @@ if __name__ == "__main__": t = sec_since_boot() rcv_times[name].append(msg.logMonoTime / 1e9) + valids[name].append(msg.valid) if t - prev_print > 1: print() for name in socket_names: dts = np.diff(rcv_times[name]) mean = np.mean(dts) - print("%s: Freq %.2f Hz, Min %.2f%%, Max %.2f%%" % (name, 1.0 / mean, np.min(dts) / mean * 100, np.max(dts) / mean * 100)) + print("%s: Freq %.2f Hz, Min %.2f%%, Max %.2f%%, valid " % (name, 1.0 / mean, np.min(dts) / mean * 100, np.max(dts) / mean * 100), all(valids[name])) prev_print = t diff --git a/selfdrive/debug/check_timings.py b/selfdrive/debug/check_timings.py new file mode 100755 index 000000000..000a73b78 --- /dev/null +++ b/selfdrive/debug/check_timings.py @@ -0,0 +1,24 @@ +#!/usr/bin/env python3 +# type: ignore +import sys +import time +import numpy as np +from collections import defaultdict, deque + +import cereal.messaging as messaging + +socks = {s: messaging.sub_sock(s, conflate=False) for s in sys.argv[1:]} +ts = defaultdict(lambda: deque(maxlen=100)) + +if __name__ == "__main__": + while True: + print() + for s, sock in socks.items(): + msgs = messaging.drain_sock(sock) + for m in msgs: + ts[s].append(m.logMonoTime / 1e6) + + if len(ts[s]) == ts[s].maxlen: + d = np.diff(ts[s]) + print(f"{s:17} {np.mean(d):.2f} {np.std(d):.2f} {np.max(d):.2f} {np.min(d):.2f}") + time.sleep(1) diff --git a/selfdrive/debug/filter_log_message.py b/selfdrive/debug/filter_log_message.py index 118a980ee..f9e37e10a 100755 --- a/selfdrive/debug/filter_log_message.py +++ b/selfdrive/debug/filter_log_message.py @@ -29,13 +29,20 @@ def print_logmessage(t, msg, min_level): log = json.loads(msg) if log['levelnum'] >= min_level: print(f"[{t / 1e9:.6f}] {log['filename']}:{log.get('lineno', '')} - {log.get('funcname', '')}: {log['msg']}") + if 'exc_info' in log: + print(log['exc_info']) except json.decoder.JSONDecodeError: print(f"[{t / 1e9:.6f}] decode error: {msg}") def print_androidlog(t, msg): source = ANDROID_LOG_SOURCE[msg.id] - print(f"[{t / 1e9:.6f}] {source} {msg.pid} {msg.tag} - {msg.message}") + try: + m = json.loads(msg.message)['MESSAGE'] + except Exception: + m = msg.message + + print(f"[{t / 1e9:.6f}] {source} {msg.pid} {msg.tag} - {m}") if __name__ == "__main__": @@ -49,7 +56,7 @@ if __name__ == "__main__": logs = None if len(args.route): r = Route(args.route[0]) - logs = r.qlog_paths() + logs = [q if r is None else r for (q, r) in zip(r.qlog_paths(), r.log_paths())] if len(args.route) == 2 and logs: n = int(args.route[1]) diff --git a/selfdrive/hardware/base.py b/selfdrive/hardware/base.py index d155f63b5..0a1976d0c 100644 --- a/selfdrive/hardware/base.py +++ b/selfdrive/hardware/base.py @@ -111,5 +111,21 @@ class HardwareBase: pass @abstractmethod - def set_power_save(self, enabled): + def set_power_save(self, powersave_enabled): + pass + + @abstractmethod + def get_gpu_usage_percent(self): + pass + + @abstractmethod + def get_modem_version(self): + pass + + @abstractmethod + def initialize_hardware(self): + pass + + @abstractmethod + def get_networks(self): pass diff --git a/selfdrive/hardware/eon/hardware.h b/selfdrive/hardware/eon/hardware.h index afd1f77be..bcd1aaba7 100644 --- a/selfdrive/hardware/eon/hardware.h +++ b/selfdrive/hardware/eon/hardware.h @@ -50,7 +50,7 @@ public: } static void close_activities() { - if(launched_activity){ + if(launched_activity) { std::system("pm disable com.android.settings && pm enable com.android.settings"); } } diff --git a/selfdrive/hardware/eon/hardware.py b/selfdrive/hardware/eon/hardware.py index 1aefde26e..b555ae351 100644 --- a/selfdrive/hardware/eon/hardware.py +++ b/selfdrive/hardware/eon/hardware.py @@ -2,8 +2,10 @@ import binascii import itertools import os import re +import serial import struct import subprocess +from typing import List, Union from cereal import log from selfdrive.hardware.base import HardwareBase, ThermalConfig @@ -11,8 +13,9 @@ from selfdrive.hardware.base import HardwareBase, ThermalConfig NetworkType = log.DeviceState.NetworkType NetworkStrength = log.DeviceState.NetworkStrength +MODEM_PATH = "/dev/smd11" -def service_call(call): +def service_call(call: List[str]) -> Union[bytes, None]: try: ret = subprocess.check_output(["service", "call", *call], encoding='utf8').strip() if 'Parcel' not in ret: @@ -22,31 +25,29 @@ def service_call(call): return None -def parse_service_call_unpack(r, fmt): +def parse_service_call_unpack(r, fmt) -> Union[bytes, None]: try: return struct.unpack(fmt, r)[0] except Exception: return None -def parse_service_call_string(r): +def parse_service_call_string(r: bytes) -> Union[str, None]: try: r = r[8:] # Cut off length field - r = r.decode('utf_16_be') + r_str = r.decode('utf_16_be') # All pairs of two characters seem to be swapped. Not sure why result = "" - for a, b, in itertools.zip_longest(r[::2], r[1::2], fillvalue='\x00'): - result += b + a + for a, b, in itertools.zip_longest(r_str[::2], r_str[1::2], fillvalue='\x00'): + result += b + a - result = result.replace('\x00', '') - - return result + return result.replace('\x00', '') except Exception: return None -def parse_service_call_bytes(ret): +def parse_service_call_bytes(ret: str) -> Union[bytes, None]: try: r = b"" for hex_part in re.findall(r'[ (]([0-9a-f]{8})', ret): @@ -56,8 +57,11 @@ def parse_service_call_bytes(ret): return None -def getprop(key): - return subprocess.check_output(["getprop", key], encoding='utf8').strip() +def getprop(key: str) -> Union[str, None]: + try: + return subprocess.check_output(["getprop", key], encoding='utf8').strip() + except subprocess.CalledProcessError: + return None class Android(HardwareBase): @@ -131,7 +135,22 @@ class Android(HardwareBase): } def get_network_info(self): - return None + msg = log.DeviceState.NetworkInfo.new_message() + msg.state = getprop("gsm.sim.state") or "" + msg.technology = getprop("gsm.network.type") or "" + msg.operator = getprop("gsm.sim.operator.numeric") or "" + + try: + modem = serial.Serial(MODEM_PATH, 115200, timeout=0.1) + modem.write(b"AT$QCRSRP?\r") + msg.extra = modem.read_until(b"OK\r\n").decode('utf-8') + + rsrp = msg.extra.split("$QCRSRP: ")[1].split("\r")[0].split(",") + msg.channel = int(rsrp[1]) + except Exception: + pass + + return msg def get_network_type(self): wifi_check = parse_service_call_string(service_call(["connectivity", "2"])) @@ -356,5 +375,22 @@ class Android(HardwareBase): with open("/sys/class/leds/lcd-backlight/brightness", "w") as f: f.write(str(int(percentage * 2.55))) - def set_power_save(self, enabled): + def set_power_save(self, powersave_enabled): pass + + def get_gpu_usage_percent(self): + try: + used, total = open('/sys/devices/soc/b00000.qcom,kgsl-3d0/kgsl/kgsl-3d0/gpubusy').read().strip().split() + perc = 100.0 * int(used) / int(total) + return min(max(perc, 0), 100) + except Exception: + return 0 + + def get_modem_version(self): + return None + + def initialize_hardware(self): + pass + + def get_networks(self): + return None diff --git a/selfdrive/hardware/pc/hardware.py b/selfdrive/hardware/pc/hardware.py index 0240f98bb..69bca5b62 100644 --- a/selfdrive/hardware/pc/hardware.py +++ b/selfdrive/hardware/pc/hardware.py @@ -83,5 +83,17 @@ class Pc(HardwareBase): def set_screen_brightness(self, percentage): pass - def set_power_save(self, enabled): + def set_power_save(self, powersave_enabled): pass + + def get_gpu_usage_percent(self): + return 0 + + def get_modem_version(self): + return None + + def initialize_hardware(self): + pass + + def get_networks(self): + return None diff --git a/selfdrive/hardware/tici/agnos.json b/selfdrive/hardware/tici/agnos.json deleted file mode 100644 index 6d2a17f29..000000000 --- a/selfdrive/hardware/tici/agnos.json +++ /dev/null @@ -1,18 +0,0 @@ -[ - { - "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate-staging/system-5242ce2639cc846282d1f98278cf4913cf8c7fc3a7428bec8c77f72f81b9e954.img.xz", - "hash": "2468dfec011cc4121f430c7fc499fcca91ceb927fd43b47651330f1aed64c597", - "hash_raw": "5242ce2639cc846282d1f98278cf4913cf8c7fc3a7428bec8c77f72f81b9e954", - "size": 10737418240, - "sparse": true - }, - { - "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate-staging/boot-c4575f9027632b06ad2d665a6d8e4f1e9022a02a3a8ce204b5048c2dbbc5cb58.img.xz", - "hash": "c4575f9027632b06ad2d665a6d8e4f1e9022a02a3a8ce204b5048c2dbbc5cb58", - "hash_raw": "c4575f9027632b06ad2d665a6d8e4f1e9022a02a3a8ce204b5048c2dbbc5cb58", - "size": 14772224, - "sparse": false - } -] diff --git a/selfdrive/hardware/tici/agnos.py b/selfdrive/hardware/tici/agnos.py deleted file mode 100755 index b9ec022cb..000000000 --- a/selfdrive/hardware/tici/agnos.py +++ /dev/null @@ -1,174 +0,0 @@ -#!/usr/bin/env python3 -import json -import lzma -import hashlib -import requests -import struct -import subprocess -import os -from typing import Generator - -from common.spinner import Spinner - - -class StreamingDecompressor: - def __init__(self, url: str) -> None: - self.buf = b"" - - self.req = requests.get(url, stream=True, headers={'Accept-Encoding': None}) - self.it = self.req.iter_content(chunk_size=1024 * 1024) - self.decompressor = lzma.LZMADecompressor(format=lzma.FORMAT_AUTO) - self.eof = False - self.sha256 = hashlib.sha256() - - def read(self, length: int) -> bytes: - while len(self.buf) < length: - self.req.raise_for_status() - - try: - compressed = next(self.it) - except StopIteration: - self.eof = True - break - out = self.decompressor.decompress(compressed) - self.buf += out - - result = self.buf[:length] - self.buf = self.buf[length:] - - self.sha256.update(result) - return result - -SPARSE_CHUNK_FMT = struct.Struct('H2xI4x') -def unsparsify(f: StreamingDecompressor) -> Generator[bytes, None, None]: - # https://source.android.com/devices/bootloader/images#sparse-format - magic = struct.unpack("I", f.read(4))[0] - assert(magic == 0xed26ff3a) - - # Version - major = struct.unpack("H", f.read(2))[0] - minor = struct.unpack("H", f.read(2))[0] - assert(major == 1 and minor == 0) - - f.read(2) # file header size - f.read(2) # chunk header size - - block_sz = struct.unpack("I", f.read(4))[0] - f.read(4) # total blocks - num_chunks = struct.unpack("I", f.read(4))[0] - f.read(4) # crc checksum - - for _ in range(num_chunks): - chunk_type, out_blocks = SPARSE_CHUNK_FMT.unpack(f.read(12)) - - if chunk_type == 0xcac1: # Raw - # TODO: yield in smaller chunks. Yielding only block_sz is too slow. Largest observed data chunk is 252 MB. - yield f.read(out_blocks * block_sz) - elif chunk_type == 0xcac2: # Fill - filler = f.read(4) * (block_sz // 4) - for _ in range(out_blocks): - yield filler - elif chunk_type == 0xcac3: # Don't care - yield b"" - else: - raise Exception("Unhandled sparse chunk type") - - -def flash_partition(cloudlog, spinner, target_slot, partition): - cloudlog.info(f"Downloading and writing {partition['name']}") - - downloader = StreamingDecompressor(partition['url']) - with open(f"/dev/disk/by-partlabel/{partition['name']}{target_slot}", 'wb+') as out: - partition_size = partition['size'] - - # Check if partition is already flashed - out.seek(partition_size) - if out.read(64) == partition['hash_raw'].lower().encode(): - cloudlog.info(f"Already flashed {partition['name']}") - return - - # Clear hash before flashing - out.seek(partition_size) - out.write(b"\x00" * 64) - out.seek(0) - os.sync() - - # Flash partition - if partition['sparse']: - raw_hash = hashlib.sha256() - for chunk in unsparsify(downloader): - raw_hash.update(chunk) - out.write(chunk) - - if spinner is not None: - spinner.update_progress(out.tell(), partition_size) - - if raw_hash.hexdigest().lower() != partition['hash_raw'].lower(): - raise Exception(f"Unsparse hash mismatch '{raw_hash.hexdigest().lower()}'") - else: - while not downloader.eof: - out.write(downloader.read(1024 * 1024)) - - if spinner is not None: - spinner.update_progress(out.tell(), partition_size) - - if downloader.sha256.hexdigest().lower() != partition['hash'].lower(): - raise Exception("Uncompressed hash mismatch") - - if out.tell() != partition['size']: - raise Exception("Uncompressed size mismatch") - - # Write hash after successfull flash - os.sync() - out.write(partition['hash_raw'].lower().encode()) - - -def flash_agnos_update(manifest_path, cloudlog, spinner=None): - update = json.load(open(manifest_path)) - - current_slot = subprocess.check_output(["abctl", "--boot_slot"], encoding='utf-8').strip() - target_slot = "_b" if current_slot == "_a" else "_a" - target_slot_number = "0" if target_slot == "_a" else "1" - - cloudlog.info(f"Current slot {current_slot}, target slot {target_slot}") - - # set target slot as unbootable - os.system(f"abctl --set_unbootable {target_slot_number}") - - for partition in update: - success = False - - for retries in range(10): - try: - flash_partition(cloudlog, spinner, target_slot, partition) - success = True - break - - except requests.exceptions.RequestException: - cloudlog.exception("Failed") - spinner.update("Waiting for internet...") - cloudlog.info(f"Failed to download {partition['name']}, retrying ({retries})") - time.sleep(10) - - if not success: - cloudlog.info(f"Failed to flash {partition['name']}, aborting") - raise Exception("Maximum retries exceeded") - - cloudlog.info(f"AGNOS ready on slot {target_slot}") - - -if __name__ == "__main__": - import logging - import time - import sys - - if len(sys.argv) != 2: - print("Usage: ./agnos.py ") - exit(1) - - spinner = Spinner() - spinner.update("Updating AGNOS") - time.sleep(5) - - logging.basicConfig(level=logging.INFO) - flash_agnos_update(sys.argv[1], logging, spinner) diff --git a/selfdrive/hardware/tici/amplifier.py b/selfdrive/hardware/tici/amplifier.py new file mode 100755 index 000000000..b0c201c07 --- /dev/null +++ b/selfdrive/hardware/tici/amplifier.py @@ -0,0 +1,100 @@ +#!/usr/bin/env python +from smbus2 import SMBus +from collections import namedtuple + +# https://datasheets.maximintegrated.com/en/ds/MAX98089.pdf + +AmpConfig = namedtuple('AmpConfig', ['name', 'value', 'register', 'offset', 'mask']) +EQParams = namedtuple('EQParams', ['K', 'k1', 'k2', 'c1', 'c2']) + +def configs_from_eq_params(base, eq_params): + return [ + AmpConfig("K (high)", (eq_params.K >> 8), base, 0, 0xFF), + AmpConfig("K (low)", (eq_params.K & 0xFF), base + 1, 0, 0xFF), + AmpConfig("k1 (high)", (eq_params.k1 >> 8), base + 2, 0, 0xFF), + AmpConfig("k1 (low)", (eq_params.k1 & 0xFF), base + 3, 0, 0xFF), + AmpConfig("k2 (high)", (eq_params.k2 >> 8), base + 4, 0, 0xFF), + AmpConfig("k2 (low)", (eq_params.k2 & 0xFF), base + 5, 0, 0xFF), + AmpConfig("c1 (high)", (eq_params.c1 >> 8), base + 6, 0, 0xFF), + AmpConfig("c1 (low)", (eq_params.c1 & 0xFF), base + 7, 0, 0xFF), + AmpConfig("c2 (high)", (eq_params.c2 >> 8), base + 8, 0, 0xFF), + AmpConfig("c2 (low)", (eq_params.c2 & 0xFF), base + 9, 0, 0xFF), + ] + +BASE_CONFIG = [ + AmpConfig("MCLK prescaler", 0b01, 0x10, 4, 0b00110000), + AmpConfig("PM: enable speakers", 0b11, 0x4D, 4, 0b00110000), + AmpConfig("PM: enable DACs", 0b11, 0x4D, 0, 0b00000011), + AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111), + AmpConfig("Right Speaker Mixer Gain", 0b00, 0x2D, 2, 0b00001100), + AmpConfig("Enable PLL1", 0b1, 0x12, 7, 0b10000000), + AmpConfig("Enable PLL2", 0b1, 0x1A, 7, 0b10000000), + AmpConfig("DAI1: I2S mode", 0b00100, 0x14, 2, 0b01111100), + AmpConfig("DAI2: I2S mode", 0b00100, 0x1C, 2, 0b01111100), + AmpConfig("Right speaker output volume", 0x1F, 0x3E, 0, 0b00011111), + AmpConfig("DAI1 Passband filtering: music mode", 0b1, 0x18, 7, 0b10000000), + AmpConfig("DAI1 voice mode gain (DV1G)", 0b00, 0x2F, 4, 0b00110000), + AmpConfig("DAI1 attenuation (DV1)", 0x0, 0x2F, 0, 0b00001111), + AmpConfig("DAI2 attenuation (DV2)", 0x0, 0x31, 0, 0b00001111), + AmpConfig("DAI2: DC blocking", 0b1, 0x20, 0, 0b00000001), + AmpConfig("DAI2: High sample rate", 0b0, 0x20, 3, 0b00001000), + AmpConfig("ALC enable", 0b0, 0x43, 7, 0b10000000), + AmpConfig("ALC/excursion limiter release time", 0b101, 0x43, 4, 0b01110000), + AmpConfig("DAI1 EQ enable", 0b0, 0x49, 0, 0b00000001), + AmpConfig("DAI2 EQ enable", 0b1, 0x49, 1, 0b00000010), + AmpConfig("DAI2 EQ clip detection disabled", 0b0, 0x32, 4, 0b00010000), + AmpConfig("DAI2 EQ attenuation", 0x5, 0x32, 0, 0b00001111), + AmpConfig("Excursion limiter upper corner freq", 0b100, 0x41, 4, 0b01110000), + AmpConfig("Excursion limiter lower corner freq", 0b00, 0x41, 0, 0b00000011), + AmpConfig("Excursion limiter threshold", 0b000, 0x42, 0, 0b00001111), + AmpConfig("Distortion limit (THDCLP)", 0x6, 0x46, 4, 0b11110000), + AmpConfig("Distortion limiter release time constant", 0b0, 0x46, 0, 0b00000001), + AmpConfig("Right DAC input mixer: DAI1 left", 0b0, 0x22, 3, 0b00001000), + AmpConfig("Right DAC input mixer: DAI1 right", 0b0, 0x22, 2, 0b00000100), + AmpConfig("Right DAC input mixer: DAI2 left", 0b1, 0x22, 1, 0b00000010), + AmpConfig("Right DAC input mixer: DAI2 right", 0b0, 0x22, 0, 0b00000001), + AmpConfig("DAI1 audio port selector", 0b10, 0x16, 6, 0b11000000), + AmpConfig("DAI2 audio port selector", 0b01, 0x1E, 6, 0b11000000), + AmpConfig("Enable left digital microphone", 0b1, 0x48, 5, 0b00100000), + AmpConfig("Enable right digital microphone", 0b1, 0x48, 4, 0b00010000), +] + +BASE_CONFIG += configs_from_eq_params(0x84, EQParams(0x65C4, 0xC07C, 0x3D66, 0x07D9, 0x120F)) +BASE_CONFIG += configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF)) +BASE_CONFIG += configs_from_eq_params(0x98, EQParams(0x2822, 0xC1C7, 0x3B50, 0x0EF8, 0x180A)) +BASE_CONFIG += configs_from_eq_params(0xA2, EQParams(0x1009, 0xC5C2, 0x271F, 0x1A87, 0x32A6)) +BASE_CONFIG += configs_from_eq_params(0xAC, EQParams(0x2000, 0xCA1E, 0x4000, 0x2287, 0x0000)) + +class Amplifier: + AMP_I2C_BUS = 0 + AMP_ADDRESS = 0x10 + + def __init__(self, debug=False): + self.debug = debug + + def set_config(self, config): + with SMBus(self.AMP_I2C_BUS) as bus: + if self.debug: + print(f"Setting \"{config.name}\" to {config.value}:") + + old_value = bus.read_byte_data(self.AMP_ADDRESS, config.register, force=True) + new_value = (old_value & (~config.mask)) | ((config.value << config.offset) & config.mask) + bus.write_byte_data(self.AMP_ADDRESS, config.register, new_value, force=True) + + if self.debug: + print(f" Changed {hex(config.register)}: {hex(old_value)} -> {hex(new_value)}") + + def set_global_shutdown(self, amp_disabled): + self.set_config(AmpConfig("Global shutdown", 0b0 if amp_disabled else 0b1, 0x51, 7, 0b10000000)) + + def initialize_configuration(self): + for config in BASE_CONFIG: + self.set_config(config) + + # Re-init amp + self.set_global_shutdown(amp_disabled=True) + self.set_global_shutdown(amp_disabled=False) + + +if __name__ == "__main__": + Amplifier(debug=True).initialize_configuration() diff --git a/selfdrive/hardware/tici/hardware.h b/selfdrive/hardware/tici/hardware.h deleted file mode 100644 index 0ff73b840..000000000 --- a/selfdrive/hardware/tici/hardware.h +++ /dev/null @@ -1,32 +0,0 @@ -#pragma once - -#include -#include - -#include "selfdrive/common/params.h" -#include "selfdrive/common/util.h" -#include "selfdrive/hardware/base.h" - -class HardwareTici : public HardwareNone { -public: - static constexpr float MAX_VOLUME = 0.5; - static constexpr float MIN_VOLUME = 0.4; - static bool TICI() { return true; } - static std::string get_os_version() { - return "AGNOS " + util::read_file("/VERSION"); - }; - - static void reboot() { std::system("sudo reboot"); }; - static void poweroff() { std::system("sudo poweroff"); }; - static void set_brightness(int percent) { - std::ofstream brightness_control("/sys/class/backlight/panel0-backlight/brightness"); - if (brightness_control.is_open()) { - brightness_control << (percent * (int)(1023/100.)) << "\n"; - brightness_control.close(); - } - }; - static void set_display_power(bool on) {}; - - static bool get_ssh_enabled() { return Params().getBool("SshEnabled"); }; - static void set_ssh_enabled(bool enabled) { Params().putBool("SshEnabled", enabled); }; -}; diff --git a/selfdrive/hardware/tici/hardware.py b/selfdrive/hardware/tici/hardware.py index 0eef97305..ac41cbc3d 100644 --- a/selfdrive/hardware/tici/hardware.py +++ b/selfdrive/hardware/tici/hardware.py @@ -1,11 +1,13 @@ import os +from functools import cached_property from enum import IntEnum import subprocess from pathlib import Path -from smbus2 import SMBus from cereal import log from selfdrive.hardware.base import HardwareBase, ThermalConfig +from selfdrive.hardware.tici.amplifier import Amplifier +from selfdrive.hardware.tici import iwlist NM = 'org.freedesktop.NetworkManager' NM_CON_ACT = NM + '.Connection.Active' @@ -42,22 +44,23 @@ NetworkStrength = log.DeviceState.NetworkStrength MM_MODEM_ACCESS_TECHNOLOGY_UMTS = 1 << 5 MM_MODEM_ACCESS_TECHNOLOGY_LTE = 1 << 14 -AMP_I2C_BUS = 0 -AMP_ADDRESS = 0x10 - -def write_amplifier_reg(reg, val, offset, mask): - with SMBus(AMP_I2C_BUS) as bus: - v = bus.read_byte_data(AMP_ADDRESS, reg, force=True) - v = (v & (~mask)) | ((val << offset) & mask) - bus.write_byte_data(AMP_ADDRESS, reg, v, force=True) - class Tici(HardwareBase): - def __init__(self): + @cached_property + def bus(self): import dbus # pylint: disable=import-error + return dbus.SystemBus() - self.bus = dbus.SystemBus() - self.nm = self.bus.get_object(NM, '/org/freedesktop/NetworkManager') - self.mm = self.bus.get_object(MM, '/org/freedesktop/ModemManager1') + @cached_property + def nm(self): + return self.bus.get_object(NM, '/org/freedesktop/NetworkManager') + + @cached_property + def mm(self): + return self.bus.get_object(MM, '/org/freedesktop/ModemManager1') + + @cached_property + def amplifier(self): + return Amplifier() def get_os_version(self): with open("/VERSION") as f: @@ -85,19 +88,27 @@ class Tici(HardwareBase): try: primary_connection = self.nm.Get(NM, 'PrimaryConnection', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) primary_connection = self.bus.get_object(NM, primary_connection) - tp = primary_connection.Get(NM_CON_ACT, 'Type', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) + primary_type = primary_connection.Get(NM_CON_ACT, 'Type', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) + primary_id = primary_connection.Get(NM_CON_ACT, 'Id', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - if tp in ['802-3-ethernet', '802-11-wireless']: + if primary_type == '802-3-ethernet': + return NetworkType.ethernet + elif primary_type == '802-11-wireless' and primary_id != 'Hotspot': return NetworkType.wifi - elif tp in ['gsm']: - modem = self.get_modem() - access_t = modem.Get(MM_MODEM, 'AccessTechnologies', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) - if access_t >= MM_MODEM_ACCESS_TECHNOLOGY_LTE: - return NetworkType.cell4G - elif access_t >= MM_MODEM_ACCESS_TECHNOLOGY_UMTS: - return NetworkType.cell3G - else: - return NetworkType.cell2G + else: + active_connections = self.nm.Get(NM, 'ActiveConnections', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) + for conn in active_connections: + c = self.bus.get_object(NM, conn) + tp = c.Get(NM_CON_ACT, 'Type', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) + if tp == 'gsm': + modem = self.get_modem() + access_t = modem.Get(MM_MODEM, 'AccessTechnologies', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) + if access_t >= MM_MODEM_ACCESS_TECHNOLOGY_LTE: + return NetworkType.cell4G + elif access_t >= MM_MODEM_ACCESS_TECHNOLOGY_UMTS: + return NetworkType.cell3G + else: + return NetworkType.cell2G except Exception: pass @@ -205,6 +216,13 @@ class Tici(HardwareBase): return network_strength + def get_modem_version(self): + try: + modem = self.get_modem() + return modem.Get(MM_MODEM, 'Revision', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) + except Exception: + return None + # We don't have a battery, so let's use some sane constants def get_battery_capacity(self): return 100 @@ -245,16 +263,49 @@ class Tici(HardwareBase): except Exception: pass - def set_power_save(self, enabled): + def set_power_save(self, powersave_enabled): # amplifier, 100mW at idle - write_amplifier_reg(0x51, 0b0 if enabled else 0b1, 7, 0b10000000) + self.amplifier.set_global_shutdown(amp_disabled=powersave_enabled) # offline big cluster, leave core 4 online for boardd for i in range(5, 8): # TODO: fix permissions with udev - val = "0" if enabled else "1" + val = "0" if powersave_enabled else "1" os.system(f"sudo su -c 'echo {val} > /sys/devices/system/cpu/cpu{i}/online'") -if __name__ == "__main__": - import sys - Tici().set_power_save(bool(int(sys.argv[1]))) + def get_gpu_usage_percent(self): + try: + used, total = open('/sys/class/kgsl/kgsl-3d0/gpubusy').read().strip().split() + return 100.0 * int(used) / int(total) + except Exception: + return 0 + + def initialize_hardware(self): + self.amplifier.initialize_configuration() + + def get_networks(self): + r = {} + + wlan = iwlist.scan() + if wlan is not None: + r['wlan'] = wlan + + lte_info = self.get_network_info() + if lte_info is not None: + extra = lte_info['extra'] + + # ,"LTE",,,,,,,, + # ,,,,,,, + if 'LTE' in extra: + extra = extra.split(',') + try: + r['lte'] = [{ + "mcc": int(extra[3]), + "mnc": int(extra[4]), + "cid": int(extra[5], 16), + "nmr": [{"pci": int(extra[6]), "earfcn": int(extra[7])}], + }] + except (ValueError, IndexError): + pass + + return r diff --git a/selfdrive/hardware/tici/iwlist.py b/selfdrive/hardware/tici/iwlist.py new file mode 100644 index 000000000..1e7c428b4 --- /dev/null +++ b/selfdrive/hardware/tici/iwlist.py @@ -0,0 +1,35 @@ +import subprocess + + +def scan(interface="wlan0"): + result = [] + try: + r = subprocess.check_output(["iwlist", interface, "scan"], encoding='utf8') + + mac = None + for line in r.split('\n'): + if "Address" in line: + # Based on the adapter eithere a percentage or dBm is returned + # Add previous network in case no dBm signal level was seen + if mac is not None: + result.append({"mac": mac}) + mac = None + + mac = line.split(' ')[-1] + elif "dBm" in line: + try: + level = line.split('Signal level=')[1] + rss = int(level.split(' ')[0]) + result.append({"mac": mac, "rss": rss}) + mac = None + except ValueError: + continue + + # Add last network if no dBm was found + if mac is not None: + result.append({"mac": mac}) + + return result + + except Exception: + return None diff --git a/selfdrive/hardware/tici/pins.py b/selfdrive/hardware/tici/pins.py deleted file mode 100644 index 7139f5e95..000000000 --- a/selfdrive/hardware/tici/pins.py +++ /dev/null @@ -1,8 +0,0 @@ -# TODO: these are also defined in a header -# GPIO pin definitions -GPIO_HUB_RST_N = 30 -GPIO_UBLOX_RST_N = 32 -GPIO_UBLOX_SAFEBOOT_N = 33 -GPIO_UBLOX_PWR_EN = 34 -GPIO_STM_RST_N = 124 -GPIO_STM_BOOT0 = 134 diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 45d036d70..d96246f94 100755 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -1,6 +1,8 @@ #include #include +#include + #include "locationd.h" using namespace EKFS; @@ -188,20 +190,20 @@ void Localizer::handle_sensors(double current_time, const capnp::List 0.1) { + if (std::abs(current_time - sensor_time) > 0.1) { LOGE("Sensor reading ignored, sensor timestamp more than 100ms off from log time"); return; } // TODO: handle messages from two IMUs at the same time - if (sensor_reading.getSource() == cereal::SensorEventData::SensorSource::LSM6DS3) { + if (sensor_reading.getSource() == cereal::SensorEventData::SensorSource::BMX055) { continue; } @@ -245,7 +247,7 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R return; } - if (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK){ + if (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK) { return; } @@ -279,7 +281,7 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R LOGE("Locationd vs ubloxLocation orientation difference too large, kalman reset"); this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos); this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); - } else if (gps_est_error > 50.0) { + } else if (gps_est_error > 100.0) { LOGE("Locationd vs ubloxLocation position difference too large, kalman reset"); this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos); } @@ -306,7 +308,7 @@ void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry VectorXd rot_calib_std = floatlist2vector(log.getRotStd()); VectorXd trans_calib_std = floatlist2vector(log.getTransStd()); - if ((rot_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK) || (trans_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK)){ + if ((rot_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK) || (trans_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK)) { return; } @@ -332,7 +334,7 @@ void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log) { if (log.getRpyCalib().size() > 0) { auto calib = floatlist2vector(log.getRpyCalib()); - if ((calib.minCoeff() < -CALIB_RPY_SANITY_CHECK) || (calib.maxCoeff() > CALIB_RPY_SANITY_CHECK)){ + if ((calib.minCoeff() < -CALIB_RPY_SANITY_CHECK) || (calib.maxCoeff() > CALIB_RPY_SANITY_CHECK)) { return; } @@ -350,19 +352,19 @@ void Localizer::reset_kalman(double current_time) { void Localizer::finite_check(double current_time) { bool all_finite = this->kf->get_x().array().isFinite().all() or this->kf->get_P().array().isFinite().all(); - if (!all_finite){ + if (!all_finite) { LOGE("Non-finite values detected, kalman reset"); this->reset_kalman(current_time); } } void Localizer::time_check(double current_time) { - if (isnan(this->last_reset_time)) { + if (std::isnan(this->last_reset_time)) { this->last_reset_time = current_time; } double filter_time = this->kf->get_filter_time(); - bool big_time_gap = !isnan(filter_time) && (current_time - filter_time > 10); - if (big_time_gap){ + bool big_time_gap = !std::isnan(filter_time) && (current_time - filter_time > 10); + if (big_time_gap) { LOGE("Time gap of over 10s detected, kalman reset"); this->reset_kalman(current_time); } @@ -467,7 +469,7 @@ int Localizer::locationd_thread() { } int main() { - setpriority(PRIO_PROCESS, 0, -20); + set_realtime_priority(5); Localizer localizer; return localizer.locationd_thread(); diff --git a/selfdrive/locationd/locationd.h b/selfdrive/locationd/locationd.h index b5b5a9bde..82b7eb6b3 100755 --- a/selfdrive/locationd/locationd.h +++ b/selfdrive/locationd/locationd.h @@ -12,7 +12,6 @@ #include "selfdrive/common/swaglog.h" #include "selfdrive/common/timing.h" #include "selfdrive/common/util.h" -#include #include "selfdrive/sensord/sensors/constants.h" #define VISION_DECIMATION 2 diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index b440cc9bb..dac95dcd7 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -87,6 +87,9 @@ class CarKalman(KalmanFilter): def generate_code(generated_dir): dim_state = CarKalman.initial_x.shape[0] name = CarKalman.name + + # vehicle models comes from The Science of Vehicle Dynamics: Handling, Braking, and Ride of Road and Race Cars + # Model used is in 6.15 with formula from 6.198 # globals global_vars = [sp.Symbol(name) for name in CarKalman.global_vars] diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index e297be3ae..3eaf8cec0 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -8,7 +8,7 @@ import numpy as np import cereal.messaging as messaging from cereal import car from common.params import Params, put_nonblocking -from common.realtime import DT_MDL +from common.realtime import set_realtime_priority, DT_MDL from common.numpy_fast import clip from selfdrive.locationd.models.car_kf import CarKalman, ObservationKind, States from selfdrive.locationd.models.constants import GENERATED_DIR @@ -73,6 +73,7 @@ class ParamsLearner: def main(sm=None, pm=None): gc.disable() + set_realtime_priority(5) if sm is None: sm = messaging.SubMaster(['liveLocationKalman', 'carState'], poll=['liveLocationKalman']) diff --git a/selfdrive/locationd/ublox_msg.h b/selfdrive/locationd/ublox_msg.h index 965359d1c..b8a48ad2d 100644 --- a/selfdrive/locationd/ublox_msg.h +++ b/selfdrive/locationd/ublox_msg.h @@ -46,7 +46,7 @@ namespace ublox { uint32_t tAccNs; } __attribute__((packed)); - inline std::string ubx_add_checksum(std::string msg){ + inline std::string ubx_add_checksum(const std::string &msg) { assert(msg.size() > 2); uint8_t ck_a = 0, ck_b = 0; diff --git a/selfdrive/locationd/ubloxd.cc b/selfdrive/locationd/ubloxd.cc index 37724b5a2..3a6c5f1a8 100644 --- a/selfdrive/locationd/ubloxd.cc +++ b/selfdrive/locationd/ubloxd.cc @@ -25,7 +25,7 @@ int main() { while (!do_exit) { Message * msg = subscriber->receive(); - if (!msg){ + if (!msg) { if (errno == EINTR) { do_exit = true; } diff --git a/selfdrive/logcatd/logcatd_systemd.cc b/selfdrive/logcatd/logcatd_systemd.cc index 6e140e4b5..7c7800dfe 100644 --- a/selfdrive/logcatd/logcatd_systemd.cc +++ b/selfdrive/logcatd/logcatd_systemd.cc @@ -29,7 +29,7 @@ int main(int argc, char *argv[]) { assert(err >= 0); // Wait for new message if we didn't receive anything - if (err == 0){ + if (err == 0) { err = sd_journal_wait(journal, 1000 * 1000); assert (err >= 0); continue; // Try again @@ -43,12 +43,12 @@ int main(int argc, char *argv[]) { size_t length; std::map kv; - SD_JOURNAL_FOREACH_DATA(journal, data, length){ + SD_JOURNAL_FOREACH_DATA(journal, data, length) { std::string str((char*)data, length); // Split "KEY=VALUE"" on "=" and put in map std::size_t found = str.find("="); - if (found != std::string::npos){ + if (found != std::string::npos) { kv[str.substr(0, found)] = str.substr(found + 1, std::string::npos); } } diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index e36012bd2..86c4473af 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -1,5 +1,4 @@ -#include - +#include #include #include "cereal/messaging/messaging.h" diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index 442d79283..6436b960b 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -1,15 +1,15 @@ #include "selfdrive/loggerd/logger.h" -#include -#include -#include -#include -#include -#include #include -#include #include +#include +#include +#include +#include +#include +#include +#include #include #include #include diff --git a/selfdrive/loggerd/logger.h b/selfdrive/loggerd/logger.h index 7a6524004..9d456680a 100644 --- a/selfdrive/loggerd/logger.h +++ b/selfdrive/loggerd/logger.h @@ -2,9 +2,9 @@ #include #include -#include -#include +#include +#include #include #include @@ -15,9 +15,12 @@ #include "selfdrive/common/swaglog.h" #include "selfdrive/hardware/hw.h" -const std::string LOG_ROOT = +const std::string DEFAULT_LOG_ROOT = Hardware::PC() ? util::getenv_default("HOME", "/.comma/media/0/realdata", "/data/media/0/realdata") : "/data/media/0/realdata"; + +const std::string LOG_ROOT = util::getenv_default("LOG_ROOT", "", DEFAULT_LOG_ROOT.c_str()); + #define LOGGER_MAX_HANDLES 16 class BZFile { diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 9a6420590..9ae49fb3b 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -1,17 +1,16 @@ -#include #include -#include #include -#include #include #include #include #include +#include #include #include #include #include +#include #include #include #include @@ -173,7 +172,7 @@ void encoder_thread(int cam_idx) { VisionIpcClient vipc_client = VisionIpcClient("camerad", cam_info.stream_type, false); while (!do_exit) { - if (!vipc_client.connect(false)){ + if (!vipc_client.connect(false)) { util::sleep_for(100); continue; } @@ -199,7 +198,7 @@ void encoder_thread(int cam_idx) { while (!do_exit) { VisionIpcBufExtra extra; VisionBuf* buf = vipc_client.recv(&extra); - if (buf == nullptr){ + if (buf == nullptr) { continue; } @@ -346,8 +345,11 @@ int main(int argc, char** argv) { qlog_states[sock] = {.counter = 0, .freq = it.decimation}; } + Params params; + // init logger logger_init(&s.logger, "rlog", true); + params.put("CurrentRoute", s.logger.route_name); // init encoders pthread_mutex_init(&s.rotate_lock, NULL); @@ -357,7 +359,7 @@ int main(int argc, char** argv) { encoder_threads.push_back(std::thread(encoder_thread, LOG_CAMERA_ID_FCAMERA)); s.rotate_state[LOG_CAMERA_ID_FCAMERA].enabled = true; - if (!Hardware::PC() && Params().getBool("RecordFront")) { + if (!Hardware::PC() && params.getBool("RecordFront")) { encoder_threads.push_back(std::thread(encoder_thread, LOG_CAMERA_ID_DCAMERA)); s.rotate_state[LOG_CAMERA_ID_DCAMERA].enabled = true; } @@ -382,7 +384,7 @@ int main(int argc, char** argv) { Message * last_msg = nullptr; while (!do_exit) { Message * msg = sock->receive(true); - if (!msg){ + if (!msg) { break; } delete last_msg; @@ -470,9 +472,10 @@ int main(int argc, char** argv) { LOGW("closing logger"); logger_close(&s.logger, &do_exit); - if (do_exit.power_failure){ + if (do_exit.power_failure) { LOGE("power failure"); sync(); + LOGE("sync done"); } // messaging cleanup diff --git a/selfdrive/loggerd/omx_encoder.cc b/selfdrive/loggerd/omx_encoder.cc index cd10bae9e..59c18c16b 100644 --- a/selfdrive/loggerd/omx_encoder.cc +++ b/selfdrive/loggerd/omx_encoder.cc @@ -2,13 +2,14 @@ #include "selfdrive/loggerd/omx_encoder.h" -#include #include -#include -#include #include #include +#include +#include +#include + #include #include #include diff --git a/selfdrive/loggerd/omx_encoder.h b/selfdrive/loggerd/omx_encoder.h index caa87101d..d7273872a 100644 --- a/selfdrive/loggerd/omx_encoder.h +++ b/selfdrive/loggerd/omx_encoder.h @@ -1,8 +1,7 @@ #pragma once -#include -#include - +#include +#include #include #include diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 9206b4315..1cbd81537 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -60,6 +60,16 @@ class Uploader(): self.last_resp = None self.last_exc = None + self.raw_size = 0 + self.raw_count = 0 + self.immediate_size = 0 + self.immediate_count = 0 + + # stats for last successfully uploaded file + self.last_time = 0 + self.last_speed = 0 + self.last_filename = "" + self.immediate_folders = ["crash/", "boot/"] self.immediate_priority = {"qlog.bz2": 0, "qcamera.ts": 1} self.high_priority = {"rlog.bz2": 0, "fcamera.hevc": 1, "dcamera.hevc": 2, "ecamera.hevc": 3} @@ -71,15 +81,22 @@ class Uploader(): return self.high_priority[name] + 100 return 1000 - def gen_upload_files(self): + def list_upload_files(self): if not os.path.isdir(self.root): return + + self.raw_size = 0 + self.raw_count = 0 + self.immediate_size = 0 + self.immediate_count = 0 + for logname in listdir_by_creation(self.root): path = os.path.join(self.root, logname) try: names = os.listdir(path) except OSError: continue + if any(name.endswith(".lock") for name in names): continue @@ -94,10 +111,21 @@ class Uploader(): is_uploaded = True # deleter could have deleted if is_uploaded: continue + + try: + if name in self.immediate_priority: + self.immediate_count += 1 + self.immediate_size += os.path.getsize(fn) + else: + self.raw_count += 1 + self.raw_size += os.path.getsize(fn) + except OSError: + pass + yield (name, key, fn) def next_file_to_upload(self, with_raw): - upload_files = list(self.gen_upload_files()) + upload_files = list(self.list_upload_files()) # try to upload qlog files first for name, key, fn in upload_files: @@ -174,15 +202,20 @@ class Uploader(): cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) success = True else: + start_time = time.monotonic() cloudlog.debug("uploading %r", fn) stat = self.normal_upload(key, fn) - if stat is not None and stat.status_code in (200, 201, 412): + if stat is not None and stat.status_code in (200, 201, 403, 412): cloudlog.event("upload_success" if stat.status_code != 412 else "upload_ignored", key=key, fn=fn, sz=sz, debug=True) try: # tag file as uploaded setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) except OSError: cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) + + self.last_filename = fn + self.last_time = time.monotonic() - start_time + self.last_speed = (sz / 1e6) / self.last_time success = True else: cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz, debug=True) @@ -190,6 +223,18 @@ class Uploader(): return success + def get_msg(self): + msg = messaging.new_message("uploaderState") + us = msg.uploaderState + us.rawQueueSize = int(self.raw_size / 1e6) + us.rawQueueCount = self.raw_count + us.immediateQueueSize = int(self.immediate_size / 1e6) + us.immediateQueueCount = self.immediate_count + us.lastTime = self.last_time + us.lastSpeed = self.last_speed + us.lastFilename = self.last_filename + return msg + def uploader_fn(exit_event): params = Params() dongle_id = params.get("DongleId", encoding='utf8') @@ -202,6 +247,7 @@ def uploader_fn(exit_event): cloudlog.warning("NVME not mounted") sm = messaging.SubMaster(['deviceState']) + pm = messaging.PubMaster(['uploaderState']) uploader = Uploader(dongle_id, ROOT) backoff = 0.1 @@ -233,6 +279,8 @@ def uploader_fn(exit_event): cloudlog.info("upload backoff %r", backoff) time.sleep(backoff + random.uniform(0, backoff)) backoff = min(backoff*2, 120) + + pm.send("uploaderState", uploader.get_msg()) cloudlog.info("upload done, success=%r", success) def main(): diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 5d6f008ef..66f836ce6 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -76,9 +76,10 @@ def build(spinner, dirty=False): # Show TextWindow spinner.close() - error_s = "\n \n".join(["\n".join(textwrap.wrap(e, 65)) for e in errors]) - with TextWindow("openpilot failed to build\n \n" + error_s) as t: - t.wait_for_exit() + if not os.getenv("CI"): + error_s = "\n \n".join(["\n".join(textwrap.wrap(e, 65)) for e in errors]) + with TextWindow("openpilot failed to build\n \n" + error_s) as t: + t.wait_for_exit() exit(1) else: break diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index e97792f7c..a967a8ed8 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -12,7 +12,7 @@ from common.basedir import BASEDIR from common.params import Params, ParamKeyType from common.text_window import TextWindow from selfdrive.boardd.set_time import set_time -from selfdrive.hardware import HARDWARE, PC, TICI +from selfdrive.hardware import HARDWARE, PC from selfdrive.manager.helpers import unblock_stdout from selfdrive.manager.process import ensure_running from selfdrive.manager.process_config import managed_processes @@ -22,6 +22,8 @@ from selfdrive.version import dirty, get_git_commit, version, origin, branch, co terms_version, training_version, comma_remote, \ get_git_branch, get_git_remote +sys.path.append(os.path.join(BASEDIR, "pyextra")) + def manager_init(): # update system time from panda @@ -37,8 +39,6 @@ def manager_init(): ] if not PC: default_params.append(("LastUpdateTime", datetime.datetime.utcnow().isoformat().encode('utf8'))) - if TICI: - default_params.append(("EnableLteOnroad", "1")) if params.get_bool("RecordFrontLock"): params.put_bool("RecordFront", True) diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py index fd8934850..588d72aa2 100644 --- a/selfdrive/manager/test/test_manager.py +++ b/selfdrive/manager/test/test_manager.py @@ -42,7 +42,7 @@ class TestManager(unittest.TestCase): for p in ALL_PROCESSES: managed_processes[p].start() - time.sleep(30) + time.sleep(10) for p in reversed(ALL_PROCESSES): state = managed_processes[p].get_process_state_msg() diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index a0548ee36..8e4f2569e 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -26,14 +26,17 @@ thneed_src = [ "runners/thneedmodel.cc", ] +use_thneed = not GetOption('no_thneed') + if arch == "aarch64" or arch == "larch64": libs += ['gsl', 'CB'] libs += ['gnustl_shared'] if arch == "aarch64" else ['pthread', 'dl'] - common_src += thneed_src - dlsym_offset = get_dlsym_offset() - lenv['CXXFLAGS'].append("-DUSE_THNEED") - lenv['CXXFLAGS'].append(f"-DDLSYM_OFFSET={dlsym_offset}") + if use_thneed: + common_src += thneed_src + dlsym_offset = get_dlsym_offset() + lenv['CXXFLAGS'].append("-DUSE_THNEED") + lenv['CXXFLAGS'].append(f"-DDLSYM_OFFSET={dlsym_offset}") else: libs += ['pthread'] @@ -58,7 +61,7 @@ else: common_model = lenv.Object(common_src) # build thneed model -if arch == "aarch64" or arch == "larch64": +if use_thneed and arch in ("aarch64", "larch64"): compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} ../../models/supercombo.dlc ../../models/supercombo.thneed --binary" @@ -75,4 +78,3 @@ lenv.Program('_modeld', [ "modeld.cc", "models/driving.cc", ]+common_model, LIBS=libs) - diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index 2bf48574f..794e3b37d 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -1,6 +1,7 @@ -MAX_DISTANCE = 140. -LANE_OFFSET = 1.8 -MAX_REL_V = 10. +IDX_N = 33 -LEAD_X_SCALE = 10 -LEAD_Y_SCALE = 10 +def index_function(idx, max_val=192): + return (max_val/1024)*(idx**2) + + +T_IDXS = [index_function(idx, max_val=10.0) for idx in range(IDX_N)] diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index 85b412609..6ae6e780c 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -1,8 +1,9 @@ -#include -#include #include #include +#include +#include + #include "cereal/visionipc/visionipc_client.h" #include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 0cfed4acd..460e33c56 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -1,6 +1,5 @@ -#include -#include - +#include +#include #include #include @@ -43,10 +42,10 @@ void calibration_thread(bool wide_camera) { while (!do_exit) { sm.update(100); - if(sm.updated("liveCalibration")){ + if(sm.updated("liveCalibration")) { auto extrinsic_matrix = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix(); Eigen::Matrix extrinsic_matrix_eigen; - for (int i = 0; i < 4*3; i++){ + for (int i = 0; i < 4*3; i++) { extrinsic_matrix_eigen(i / 4, i % 4) = extrinsic_matrix[i]; } @@ -79,7 +78,6 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client) { uint32_t frame_id = 0, last_vipc_frame_id = 0; double last = 0; - int desire = -1; uint32_t run_count = 0; while (!do_exit) { @@ -94,7 +92,7 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client) { // TODO: path planner timeout? sm.update(0); - desire = ((int)sm["lateralPlan"].getLateralPlan().getDesire()); + int desire = ((int)sm["lateralPlan"].getLateralPlan().getDesire()); frame_id = sm["roadCameraState"].getRoadCameraState().getFrameId(); if (run_model_this_iter) { diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc index 495bfe782..9def7e49e 100644 --- a/selfdrive/modeld/models/commonmodel.cc +++ b/selfdrive/modeld/models/commonmodel.cc @@ -1,54 +1,47 @@ -#include "commonmodel.h" - -#include -#include +#include "selfdrive/modeld/models/commonmodel.h" #include +#include +#include +#include #include "selfdrive/common/clutil.h" #include "selfdrive/common/mat.h" #include "selfdrive/common/timing.h" -void frame_init(ModelFrame* frame, int width, int height, - cl_device_id device_id, cl_context context) { - transform_init(&frame->transform, context, device_id); - frame->width = width; - frame->height = height; +ModelFrame::ModelFrame(cl_device_id device_id, cl_context context) { + input_frames = std::make_unique(buf_size); - frame->y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (size_t)width*height, NULL, &err)); - frame->u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (size_t)(width/2)*(height/2), NULL, &err)); - frame->v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (size_t)(width/2)*(height/2), NULL, &err)); - frame->net_input_size = ((width*height*3)/2)*sizeof(float); - frame->net_input = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, - frame->net_input_size, (void*)NULL, &err)); - loadyuv_init(&frame->loadyuv, context, device_id, width, height); + q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err)); + y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_WIDTH * MODEL_HEIGHT, NULL, &err)); + u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); + v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); + net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_FRAME_SIZE * sizeof(float), NULL, &err)); + + transform_init(&transform, context, device_id); + loadyuv_init(&loadyuv, context, device_id, MODEL_WIDTH, MODEL_HEIGHT); } -float *frame_prepare(ModelFrame* frame, cl_command_queue q, - cl_mem yuv_cl, int width, int height, - const mat3 &transform) { - transform_queue(&frame->transform, q, - yuv_cl, width, height, - frame->y_cl, frame->u_cl, frame->v_cl, - frame->width, frame->height, - transform); - loadyuv_queue(&frame->loadyuv, q, - frame->y_cl, frame->u_cl, frame->v_cl, - frame->net_input); - float *net_input_buf = (float *)CL_CHECK_ERR(clEnqueueMapBuffer(q, frame->net_input, CL_TRUE, - CL_MAP_READ, 0, frame->net_input_size, - 0, NULL, NULL, &err)); +float* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, const mat3 &transform) { + transform_queue(&this->transform, q, + yuv_cl, frame_width, frame_height, + y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, transform); + loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, net_input_cl); + + std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], sizeof(float) * MODEL_FRAME_SIZE); + clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, MODEL_FRAME_SIZE * sizeof(float), &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr); clFinish(q); - return net_input_buf; + return &input_frames[0]; } -void frame_free(ModelFrame* frame) { - transform_destroy(&frame->transform); - loadyuv_destroy(&frame->loadyuv); - CL_CHECK(clReleaseMemObject(frame->net_input)); - CL_CHECK(clReleaseMemObject(frame->v_cl)); - CL_CHECK(clReleaseMemObject(frame->u_cl)); - CL_CHECK(clReleaseMemObject(frame->y_cl)); +ModelFrame::~ModelFrame() { + transform_destroy(&transform); + loadyuv_destroy(&loadyuv); + CL_CHECK(clReleaseMemObject(net_input_cl)); + CL_CHECK(clReleaseMemObject(v_cl)); + CL_CHECK(clReleaseMemObject(u_cl)); + CL_CHECK(clReleaseMemObject(y_cl)); + CL_CHECK(clReleaseCommandQueue(q)); } void softmax(const float* input, float* output, size_t len) { diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index 281930be6..e4e6563d7 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -1,7 +1,9 @@ #pragma once -#include -#include +#include +#include + +#include #define CL_USE_DEPRECATED_OPENCL_1_2_APIS #ifdef __APPLE__ @@ -14,24 +16,28 @@ #include "selfdrive/modeld/transforms/loadyuv.h" #include "selfdrive/modeld/transforms/transform.h" +constexpr int MODEL_WIDTH = 512; +constexpr int MODEL_HEIGHT = 256; +constexpr int MODEL_FRAME_SIZE = MODEL_WIDTH * MODEL_HEIGHT * 3 / 2; + const bool send_raw_pred = getenv("SEND_RAW_PRED") != NULL; void softmax(const float* input, float* output, size_t len); float softplus(float input); float sigmoid(float input); -typedef struct ModelFrame { - Transform transform; - int width, height; - cl_mem y_cl, u_cl, v_cl; - LoadYUVState loadyuv; - cl_mem net_input; - size_t net_input_size; -} ModelFrame; +class ModelFrame { + public: + ModelFrame(cl_device_id device_id, cl_context context); + ~ModelFrame(); + float* prepare(cl_mem yuv_cl, int width, int height, const mat3& transform); -void frame_init(ModelFrame* frame, int width, int height, - cl_device_id device_id, cl_context context); -float *frame_prepare(ModelFrame* frame, cl_command_queue q, - cl_mem yuv_cl, int width, int height, - const mat3 &transform); -void frame_free(ModelFrame* frame); + const int buf_size = MODEL_FRAME_SIZE * 2; + + private: + Transform transform; + LoadYUVState loadyuv; + cl_command_queue q; + cl_mem y_cl, u_cl, v_cl, net_input_cl; + std::unique_ptr input_frames; +}; diff --git a/selfdrive/modeld/models/dmonitoring.cc b/selfdrive/modeld/models/dmonitoring.cc index 9a1b8723a..075889caa 100644 --- a/selfdrive/modeld/models/dmonitoring.cc +++ b/selfdrive/modeld/models/dmonitoring.cc @@ -1,4 +1,4 @@ -#include +#include #include "libyuv.h" @@ -6,6 +6,7 @@ #include "selfdrive/common/params.h" #include "selfdrive/common/timing.h" #include "selfdrive/hardware/hw.h" + #include "selfdrive/modeld/models/dmonitoring.h" #define MODEL_WIDTH 320 @@ -19,7 +20,7 @@ #endif void dmonitoring_init(DMonitoringModelState* s) { - const char *model_path = "../../models/dmonitoring_model_q.dlc"; + const char *model_path = Hardware::PC() ? "../../models/dmonitoring_model.dlc" : "../../models/dmonitoring_model_q.dlc"; int runtime = USE_DSP_RUNTIME; s->m = new DefaultRunModel(model_path, &s->output[0], OUTPUT_SIZE, runtime); s->is_rhd = Params().getBool("IsRHD"); @@ -165,7 +166,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_ return ret; } -void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr raw_pred){ +void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr raw_pred) { // make msg MessageBuilder msg; auto framed = msg.initEvent().initDriverState(); diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index aea0d4319..f7a72b34e 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -1,11 +1,11 @@ +#include "selfdrive/modeld/models/driving.h" -#include "driving.h" - -#include #include -#include #include +#include +#include + #include #include "selfdrive/common/clutil.h" @@ -17,10 +17,6 @@ constexpr int OTHER_META_SIZE = 32; constexpr int NUM_META_INTERVALS = 5; constexpr int META_STRIDE = 6; -constexpr int MODEL_WIDTH = 512; -constexpr int MODEL_HEIGHT = 256; -constexpr int MODEL_FRAME_SIZE = MODEL_WIDTH * MODEL_HEIGHT * 3 / 2; - constexpr int PLAN_MHP_N = 5; constexpr int PLAN_MHP_COLUMNS = 15; constexpr int PLAN_MHP_VALS = 15*33; @@ -60,13 +56,12 @@ float prev_brake_3ms2_probs[3] = {0,0,0}; // #define DUMP_YUV void model_init(ModelState* s, cl_device_id device_id, cl_context context) { - frame_init(&s->frame, MODEL_WIDTH, MODEL_HEIGHT, device_id, context); - s->input_frames = std::make_unique(MODEL_FRAME_SIZE * 2); + s->frame = new ModelFrame(device_id, context); constexpr int output_size = OUTPUT_SIZE + TEMPORAL_SIZE; s->output.resize(output_size); -#if defined(QCOM) || defined(QCOM2) +#if (defined(QCOM) || defined(QCOM2)) && defined(USE_THNEED) s->m = std::make_unique("../../models/supercombo.thneed", &s->output[0], output_size, USE_GPU_RUNTIME); #else s->m = std::make_unique("../../models/supercombo.dlc", &s->output[0], output_size, USE_GPU_RUNTIME); @@ -85,8 +80,6 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context) { s->traffic_convention[idx] = 1.0; s->m->addTrafficConvention(s->traffic_convention, TRAFFIC_CONVENTION_LEN); #endif - - s->q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err)); } ModelDataRaw model_eval_frame(ModelState* s, cl_mem yuv_cl, int width, int height, @@ -108,19 +101,8 @@ ModelDataRaw model_eval_frame(ModelState* s, cl_mem yuv_cl, int width, int heigh //for (int i = 0; i < OUTPUT_SIZE + TEMPORAL_SIZE; i++) { printf("%f ", s->output[i]); } printf("\n"); - float *new_frame_buf = frame_prepare(&s->frame, s->q, yuv_cl, width, height, transform); - memmove(&s->input_frames[0], &s->input_frames[MODEL_FRAME_SIZE], sizeof(float)*MODEL_FRAME_SIZE); - memmove(&s->input_frames[MODEL_FRAME_SIZE], new_frame_buf, sizeof(float)*MODEL_FRAME_SIZE); - s->m->execute(&s->input_frames[0], MODEL_FRAME_SIZE*2); - - #ifdef DUMP_YUV - FILE *dump_yuv_file = fopen("/sdcard/dump.yuv", "wb"); - fwrite(new_frame_buf, MODEL_HEIGHT*MODEL_WIDTH*3/2, sizeof(float), dump_yuv_file); - fclose(dump_yuv_file); - assert(1==2); - #endif - - clEnqueueUnmapMemObject(s->q, s->frame.net_input, (void*)new_frame_buf, 0, NULL, NULL); + auto net_input_buf = s->frame->prepare(yuv_cl, width, height, transform); + s->m->execute(net_input_buf, s->frame->buf_size); // net outputs ModelDataRaw net_outputs; @@ -136,8 +118,7 @@ ModelDataRaw model_eval_frame(ModelState* s, cl_mem yuv_cl, int width, int heigh } void model_free(ModelState* s) { - frame_free(&s->frame); - CL_CHECK(clReleaseCommandQueue(s->q)); + delete s->frame; } static const float *get_best_data(const float *data, int size, int group_size, int offset) { @@ -203,8 +184,8 @@ void fill_meta(cereal::ModelDataV2::MetaData::Builder meta, const float *meta_da fill_sigmoid(&meta_data[DESIRE_LEN+5], brake_4ms2_sigmoid, NUM_META_INTERVALS, META_STRIDE); fill_sigmoid(&meta_data[DESIRE_LEN+6], brake_5ms2_sigmoid, NUM_META_INTERVALS, META_STRIDE); - memmove(prev_brake_5ms2_probs, &prev_brake_5ms2_probs[1], 4*sizeof(float)); - memmove(prev_brake_3ms2_probs, &prev_brake_3ms2_probs[1], 2*sizeof(float)); + std::memmove(prev_brake_5ms2_probs, &prev_brake_5ms2_probs[1], 4*sizeof(float)); + std::memmove(prev_brake_3ms2_probs, &prev_brake_3ms2_probs[1], 2*sizeof(float)); prev_brake_5ms2_probs[4] = brake_5ms2_sigmoid[0]; prev_brake_3ms2_probs[2] = brake_3ms2_sigmoid[0]; @@ -272,17 +253,18 @@ void fill_model(cereal::ModelDataV2::Builder &framed, const ModelDataRaw &net_ou // plan const float *best_plan = get_plan_data(net_outputs.plan); float plan_t_arr[TRAJECTORY_SIZE]; + std::fill_n(plan_t_arr, TRAJECTORY_SIZE, NAN); plan_t_arr[0] = 0.0; - int xidx = 1, tidx = 0; - for (; xidx output; - std::unique_ptr input_frames; std::unique_ptr m; - cl_command_queue q; #ifdef DESIRE float prev_desire[DESIRE_LEN] = {}; float pulse_desire[DESIRE_LEN] = {}; diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 9f26ad27f..3a6e9e622 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -2,10 +2,9 @@ #include "selfdrive/modeld/runners/snpemodel.h" -#include -#include - #include +#include +#include #include "selfdrive/common/util.h" diff --git a/selfdrive/modeld/runners/thneedmodel.cc b/selfdrive/modeld/runners/thneedmodel.cc index c83a58b02..be782b974 100644 --- a/selfdrive/modeld/runners/thneedmodel.cc +++ b/selfdrive/modeld/runners/thneedmodel.cc @@ -1,6 +1,6 @@ -#include "thneedmodel.h" +#include "selfdrive/modeld/runners/thneedmodel.h" -#include +#include ThneedModel::ThneedModel(const char *path, float *loutput, size_t loutput_size, int runtime) { thneed = new Thneed(true); diff --git a/selfdrive/modeld/thneed/compile.cc b/selfdrive/modeld/thneed/compile.cc index cf15e9ceb..01a71b747 100644 --- a/selfdrive/modeld/thneed/compile.cc +++ b/selfdrive/modeld/thneed/compile.cc @@ -1,4 +1,4 @@ -#include +#include #include "selfdrive/modeld/runners/snpemodel.h" #include "selfdrive/modeld/thneed/thneed.h" @@ -16,7 +16,7 @@ int main(int argc, char* argv[]) { float state[TEMPORAL_SIZE] = {0}; float desire[DESIRE_LEN] = {0}; float traffic_convention[TRAFFIC_CONVENTION_LEN] = {0}; - float *input = (float*)calloc(0x1000000, sizeof(float));; + float *input = (float*)calloc(0x1000000, sizeof(float)); mdl.addRecurrent(state, TEMPORAL_SIZE); mdl.addDesire(desire, DESIRE_LEN); diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc index e3aa099d1..1f17c4a87 100644 --- a/selfdrive/modeld/thneed/serialize.cc +++ b/selfdrive/modeld/thneed/serialize.cc @@ -1,5 +1,4 @@ -#include - +#include #include #include "json11.hpp" diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc index 3b0138a14..89fdfe391 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed.cc @@ -1,11 +1,11 @@ #include "selfdrive/modeld/thneed/thneed.h" #include -#include -#include #include #include +#include +#include #include #include diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index eaea22e41..1ae724747 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -4,14 +4,14 @@ #define __user __attribute__(()) #endif -#include -#include -#include - +#include +#include #include #include #include +#include + #include "selfdrive/modeld/thneed/include/msm_kgsl.h" #define THNEED_RECORD 1 diff --git a/selfdrive/modeld/transforms/loadyuv.cc b/selfdrive/modeld/transforms/loadyuv.cc index d3686a667..9f3dd45aa 100644 --- a/selfdrive/modeld/transforms/loadyuv.cc +++ b/selfdrive/modeld/transforms/loadyuv.cc @@ -1,7 +1,8 @@ -#include "loadyuv.h" +#include "selfdrive/modeld/transforms/loadyuv.h" -#include -#include +#include +#include +#include void loadyuv_init(LoadYUVState* s, cl_context ctx, cl_device_id device_id, int width, int height) { memset(s, 0, sizeof(*s)); diff --git a/selfdrive/modeld/transforms/loadyuv.h b/selfdrive/modeld/transforms/loadyuv.h index 7289aeff4..a77258deb 100644 --- a/selfdrive/modeld/transforms/loadyuv.h +++ b/selfdrive/modeld/transforms/loadyuv.h @@ -1,7 +1,5 @@ #pragma once -#include - #include "selfdrive/common/clutil.h" typedef struct { diff --git a/selfdrive/modeld/transforms/transform.cc b/selfdrive/modeld/transforms/transform.cc index 6cf48220a..5f4929bab 100644 --- a/selfdrive/modeld/transforms/transform.cc +++ b/selfdrive/modeld/transforms/transform.cc @@ -1,7 +1,7 @@ -#include "transform.h" +#include "selfdrive/modeld/transforms/transform.h" -#include -#include +#include +#include #include "selfdrive/common/clutil.h" diff --git a/selfdrive/modeld/transforms/transform.h b/selfdrive/modeld/transforms/transform.h index 4a40b976a..f34613684 100644 --- a/selfdrive/modeld/transforms/transform.h +++ b/selfdrive/modeld/transforms/transform.h @@ -1,7 +1,5 @@ #pragma once -#include - #define CL_USE_DEPRECATED_OPENCL_1_2_APIS #ifdef __APPLE__ #include diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index ff7bdefb9..accaf62ae 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -39,7 +39,6 @@ _PITCH_POS_ALLOWANCE = 0.12 # rad, to not be too sensitive on positive pitch _PITCH_NATURAL_OFFSET = 0.02 # people don't seem to look straight when they drive relaxed, rather a bit up _YAW_NATURAL_OFFSET = 0.08 # people don't seem to look straight when they drive relaxed, rather a bit to the right (center of car) -_HI_STD_TIMEOUT = 5 _HI_STD_FALLBACK_TIME = 10 # fall back to wheel touch if model is uncertain for a long time _DISTRACTED_FILTER_TS = 0.25 # 0.6Hz @@ -119,7 +118,6 @@ class DriverStatus(): self.active_monitoring_mode = True self.is_model_uncertain = False self.hi_stds = 0 - self.hi_std_alert_enabled = True self.threshold_prompt = _DISTRACTED_PROMPT_TIME_TILL_TERMINAL / _DISTRACTED_TIME self._set_timers(active_monitoring=True) @@ -196,10 +194,11 @@ class DriverStatus(): self.blink.left_blink = driver_state.leftBlinkProb * (driver_state.leftEyeProb > _EYE_THRESHOLD) * (driver_state.sunglassesProb < _SG_THRESHOLD) self.blink.right_blink = driver_state.rightBlinkProb * (driver_state.rightEyeProb > _EYE_THRESHOLD) * (driver_state.sunglassesProb < _SG_THRESHOLD) - self.driver_distracted = (self._is_driver_distracted(self.pose, self.blink) > 0 and - driver_state.faceProb > _FACE_THRESHOLD and self.pose.low_std) or \ - ((driver_state.distractedPose > _E2E_POSE_THRESHOLD or driver_state.distractedEyes > _E2E_EYES_THRESHOLD) and - (self.face_detected and not self.face_partial)) + distracted_normal = (self._is_driver_distracted(self.pose, self.blink) > 0 and + driver_state.faceProb > _FACE_THRESHOLD and self.pose.low_std) + distracted_E2E = ((driver_state.distractedPose > _E2E_POSE_THRESHOLD or driver_state.distractedEyes > _E2E_EYES_THRESHOLD) and + (self.face_detected and not self.face_partial)) + self.driver_distracted = distracted_normal or distracted_E2E self.driver_distraction_filter.update(self.driver_distracted) # update offseter @@ -229,10 +228,6 @@ class DriverStatus(): driver_attentive = self.driver_distraction_filter.x < 0.37 awareness_prev = self.awareness - if self.face_detected and self.hi_stds * DT_DMON > _HI_STD_TIMEOUT and self.hi_std_alert_enabled: - events.add(EventName.driverMonitorLowAcc) - self.hi_std_alert_enabled = False # only showed once until orange prompt resets it - if (driver_attentive and self.face_detected and self.pose.low_std and self.awareness > 0): # only restore awareness when paying attention and alert is not red self.awareness = min(self.awareness + ((_RECOVERY_FACTOR_MAX-_RECOVERY_FACTOR_MIN)*(1.-self.awareness)+_RECOVERY_FACTOR_MIN)*self.step_change, 1.) @@ -242,16 +237,18 @@ class DriverStatus(): if self.awareness > self.threshold_prompt: return - # should always be counting if distracted unless at standstill and reaching orange - if (not (self.face_detected and self.hi_stds * DT_DMON <= _HI_STD_FALLBACK_TIME) or (self.driver_distraction_filter.x > 0.63 and self.driver_distracted and self.face_detected)) and \ - not (standstill and self.awareness - self.step_change <= self.threshold_prompt): - self.awareness = max(self.awareness - self.step_change, -0.1) + standstill_exemption = standstill and self.awareness - self.step_change <= self.threshold_prompt + certainly_distracted = self.driver_distraction_filter.x > 0.63 and self.driver_distracted and self.face_detected + maybe_distracted = self.hi_stds * DT_DMON > _HI_STD_FALLBACK_TIME or not self.face_detected + if certainly_distracted or maybe_distracted: + # should always be counting if distracted unless at standstill and reaching orange + if not standstill_exemption: + self.awareness = max(self.awareness - self.step_change, -0.1) alert = None if self.awareness <= 0.: # terminal red alert: disengagement required alert = EventName.driverDistracted if self.active_monitoring_mode else EventName.driverUnresponsive - self.hi_std_alert_enabled = True self.terminal_time += 1 if awareness_prev > 0.: self.terminal_alert_cnt += 1 diff --git a/selfdrive/sensord/SConscript b/selfdrive/sensord/SConscript index 0817a4d30..186e302bc 100644 --- a/selfdrive/sensord/SConscript +++ b/selfdrive/sensord/SConscript @@ -14,6 +14,7 @@ else: 'sensors/lsm6ds3_accel.cc', 'sensors/lsm6ds3_gyro.cc', 'sensors/lsm6ds3_temp.cc', + 'sensors/mmc5603nj_magn.cc', ] libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj'] if arch == "larch64": diff --git a/selfdrive/sensord/sensors/bmx055_accel.cc b/selfdrive/sensord/sensors/bmx055_accel.cc index 590fa51e8..f5d68bdee 100644 --- a/selfdrive/sensord/sensors/bmx055_accel.cc +++ b/selfdrive/sensord/sensors/bmx055_accel.cc @@ -7,17 +7,17 @@ BMX055_Accel::BMX055_Accel(I2CBus *bus) : I2CSensor(bus) {} -int BMX055_Accel::init(){ +int BMX055_Accel::init() { int ret = 0; uint8_t buffer[1]; ret = read_register(BMX055_ACCEL_I2C_REG_ID, buffer, 1); - if(ret < 0){ + if(ret < 0) { LOGE("Reading chip ID failed: %d", ret); goto fail; } - if(buffer[0] != BMX055_ACCEL_CHIP_ID){ + if(buffer[0] != BMX055_ACCEL_CHIP_ID) { LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_ACCEL_CHIP_ID); ret = -1; goto fail; @@ -25,17 +25,17 @@ int BMX055_Accel::init(){ // High bandwidth // ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_ENABLE); - // if (ret < 0){ + // if (ret < 0) { // goto fail; // } // Low bandwidth ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_DISABLE); - if (ret < 0){ + if (ret < 0) { goto fail; } ret = set_register(BMX055_ACCEL_I2C_REG_BW, BMX055_ACCEL_BW_125HZ); - if (ret < 0){ + if (ret < 0) { goto fail; } @@ -43,7 +43,7 @@ fail: return ret; } -void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event){ +void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; int len = read_register(BMX055_ACCEL_I2C_REG_X_LSB, buffer, sizeof(buffer)); diff --git a/selfdrive/sensord/sensors/bmx055_gyro.cc b/selfdrive/sensord/sensors/bmx055_gyro.cc index c8e9e3565..f0e3034e3 100644 --- a/selfdrive/sensord/sensors/bmx055_gyro.cc +++ b/selfdrive/sensord/sensors/bmx055_gyro.cc @@ -10,17 +10,17 @@ BMX055_Gyro::BMX055_Gyro(I2CBus *bus) : I2CSensor(bus) {} -int BMX055_Gyro::init(){ +int BMX055_Gyro::init() { int ret = 0; uint8_t buffer[1]; ret =read_register(BMX055_GYRO_I2C_REG_ID, buffer, 1); - if(ret < 0){ + if(ret < 0) { LOGE("Reading chip ID failed: %d", ret); goto fail; } - if(buffer[0] != BMX055_GYRO_CHIP_ID){ + if(buffer[0] != BMX055_GYRO_CHIP_ID) { LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_GYRO_CHIP_ID); ret = -1; goto fail; @@ -28,25 +28,25 @@ int BMX055_Gyro::init(){ // High bandwidth // ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_ENABLE); - // if (ret < 0){ + // if (ret < 0) { // goto fail; // } // Low bandwidth ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_DISABLE); - if (ret < 0){ + if (ret < 0) { goto fail; } // 116 Hz filter ret = set_register(BMX055_GYRO_I2C_REG_BW, BMX055_GYRO_BW_116HZ); - if (ret < 0){ + if (ret < 0) { goto fail; } // +- 125 deg/s range ret = set_register(BMX055_GYRO_I2C_REG_RANGE, BMX055_GYRO_RANGE_125); - if (ret < 0){ + if (ret < 0) { goto fail; } @@ -54,7 +54,7 @@ fail: return ret; } -void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event){ +void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; int len = read_register(BMX055_GYRO_I2C_REG_RATE_X_LSB, buffer, sizeof(buffer)); diff --git a/selfdrive/sensord/sensors/bmx055_magn.cc b/selfdrive/sensord/sensors/bmx055_magn.cc index b00feba4f..e7a8de909 100644 --- a/selfdrive/sensord/sensors/bmx055_magn.cc +++ b/selfdrive/sensord/sensors/bmx055_magn.cc @@ -65,7 +65,7 @@ static int16_t compensate_z(trim_data_t trim_data, int16_t mag_data_z, uint16_t BMX055_Magn::BMX055_Magn(I2CBus *bus) : I2CSensor(bus) {} -int BMX055_Magn::init(){ +int BMX055_Magn::init() { int ret; uint8_t buffer[1]; uint8_t trim_x1y1[2] = {0}; @@ -79,7 +79,7 @@ int BMX055_Magn::init(){ // suspend -> sleep ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0x01); - if(ret < 0){ + if(ret < 0) { LOGE("Enabling power failed: %d", ret); goto fail; } @@ -87,12 +87,12 @@ int BMX055_Magn::init(){ // read chip ID ret = read_register(BMX055_MAGN_I2C_REG_ID, buffer, 1); - if(ret < 0){ + if(ret < 0) { LOGE("Reading chip ID failed: %d", ret); goto fail; } - if(buffer[0] != BMX055_MAGN_CHIP_ID){ + if(buffer[0] != BMX055_MAGN_CHIP_ID) { LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_MAGN_CHIP_ID); return -1; } @@ -139,12 +139,12 @@ int BMX055_Magn::init(){ // Chose NXY = 7, NZ = 12, which gives 125 Hz, // and has the same ratio as the high accuracy preset ret = set_register(BMX055_MAGN_I2C_REG_REPXY, (7 - 1) / 2); - if (ret < 0){ + if (ret < 0) { goto fail; } ret = set_register(BMX055_MAGN_I2C_REG_REPZ, 12 - 1); - if (ret < 0){ + if (ret < 0) { goto fail; } @@ -155,7 +155,7 @@ int BMX055_Magn::init(){ return ret; } -bool BMX055_Magn::perform_self_test(){ +bool BMX055_Magn::perform_self_test() { uint8_t buffer[8]; int16_t x, y; int16_t neg_z, pos_z; @@ -189,16 +189,16 @@ bool BMX055_Magn::perform_self_test(){ int16_t diff = pos_z - neg_z; bool passed = (diff > 180) && (diff < 240); - if (!passed){ + if (!passed) { LOGE("self test failed: neg %d pos %d diff %d", neg_z, pos_z, diff); } return passed; } -bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *z){ +bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *z) { bool ready = buffer[6] & 0x1; - if (ready){ + if (ready) { int16_t mdata_x = (int16_t) (((int16_t)buffer[1] << 8) | buffer[0]) >> 3; int16_t mdata_y = (int16_t) (((int16_t)buffer[3] << 8) | buffer[2]) >> 3; int16_t mdata_z = (int16_t) (((int16_t)buffer[5] << 8) | buffer[4]) >> 1; @@ -213,7 +213,7 @@ bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t * } -void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event){ +void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[8]; int16_t _x, _y, x, y, z; @@ -221,7 +221,7 @@ void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event){ int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); assert(len == sizeof(buffer)); - if (parse_xyz(buffer, &_x, &_y, &z)){ + if (parse_xyz(buffer, &_x, &_y, &z)) { event.setSource(cereal::SensorEventData::SensorSource::BMX055); event.setVersion(2); event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); diff --git a/selfdrive/sensord/sensors/bmx055_temp.cc b/selfdrive/sensord/sensors/bmx055_temp.cc index b5cb893a0..339a987ce 100644 --- a/selfdrive/sensord/sensors/bmx055_temp.cc +++ b/selfdrive/sensord/sensors/bmx055_temp.cc @@ -8,17 +8,17 @@ BMX055_Temp::BMX055_Temp(I2CBus *bus) : I2CSensor(bus) {} -int BMX055_Temp::init(){ +int BMX055_Temp::init() { int ret = 0; uint8_t buffer[1]; ret = read_register(BMX055_ACCEL_I2C_REG_ID, buffer, 1); - if(ret < 0){ + if(ret < 0) { LOGE("Reading chip ID failed: %d", ret); goto fail; } - if(buffer[0] != BMX055_ACCEL_CHIP_ID){ + if(buffer[0] != BMX055_ACCEL_CHIP_ID) { LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_ACCEL_CHIP_ID); ret = -1; goto fail; @@ -28,7 +28,7 @@ fail: return ret; } -void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event){ +void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[1]; int len = read_register(BMX055_ACCEL_I2C_REG_TEMP, buffer, sizeof(buffer)); diff --git a/selfdrive/sensord/sensors/file_sensor.cc b/selfdrive/sensord/sensors/file_sensor.cc index b993349e8..812a41fa8 100644 --- a/selfdrive/sensord/sensors/file_sensor.cc +++ b/selfdrive/sensord/sensors/file_sensor.cc @@ -9,6 +9,6 @@ int FileSensor::init() { return file.is_open() ? 0 : 1; } -FileSensor::~FileSensor(){ +FileSensor::~FileSensor() { file.close(); } diff --git a/selfdrive/sensord/sensors/i2c_sensor.cc b/selfdrive/sensord/sensors/i2c_sensor.cc index 0e7b8ef98..40dfa4a73 100644 --- a/selfdrive/sensord/sensors/i2c_sensor.cc +++ b/selfdrive/sensord/sensors/i2c_sensor.cc @@ -1,23 +1,28 @@ #include "i2c_sensor.h" -int16_t read_12_bit(uint8_t lsb, uint8_t msb){ +int16_t read_12_bit(uint8_t lsb, uint8_t msb) { uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb & 0xF0); return int16_t(combined) / (1 << 4); } -int16_t read_16_bit(uint8_t lsb, uint8_t msb){ +int16_t read_16_bit(uint8_t lsb, uint8_t msb) { uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb); return int16_t(combined); } - -I2CSensor::I2CSensor(I2CBus *bus) : bus(bus){ +int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0) { + uint32_t combined = (uint32_t(b0) << 16) | (uint32_t(b1) << 8) | uint32_t(b2); + return int32_t(combined) / (1 << 4); } -int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len){ + +I2CSensor::I2CSensor(I2CBus *bus) : bus(bus) { +} + +int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len) { return bus->read_register(get_device_address(), register_address, buffer, len); } -int I2CSensor::set_register(uint register_address, uint8_t data){ +int I2CSensor::set_register(uint register_address, uint8_t data) { return bus->set_register(get_device_address(), register_address, data); } diff --git a/selfdrive/sensord/sensors/i2c_sensor.h b/selfdrive/sensord/sensors/i2c_sensor.h index 98e2e2f85..83c66eac8 100644 --- a/selfdrive/sensord/sensors/i2c_sensor.h +++ b/selfdrive/sensord/sensors/i2c_sensor.h @@ -9,6 +9,7 @@ int16_t read_12_bit(uint8_t lsb, uint8_t msb); int16_t read_16_bit(uint8_t lsb, uint8_t msb); +int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0); class I2CSensor : public Sensor { diff --git a/selfdrive/sensord/sensors/light_sensor.cc b/selfdrive/sensord/sensors/light_sensor.cc index 9601a7818..4d00d37bd 100644 --- a/selfdrive/sensord/sensors/light_sensor.cc +++ b/selfdrive/sensord/sensors/light_sensor.cc @@ -5,7 +5,7 @@ #include "selfdrive/common/timing.h" #include "selfdrive/sensord/sensors/constants.h" -void LightSensor::get_event(cereal::SensorEventData::Builder &event){ +void LightSensor::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); file.clear(); file.seekg(0); diff --git a/selfdrive/sensord/sensors/lsm6ds3_accel.cc b/selfdrive/sensord/sensors/lsm6ds3_accel.cc index 27b882a4f..83222858e 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_accel.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_accel.cc @@ -7,25 +7,29 @@ LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus) : I2CSensor(bus) {} -int LSM6DS3_Accel::init(){ +int LSM6DS3_Accel::init() { int ret = 0; uint8_t buffer[1]; ret = read_register(LSM6DS3_ACCEL_I2C_REG_ID, buffer, 1); - if(ret < 0){ + if(ret < 0) { LOGE("Reading chip ID failed: %d", ret); goto fail; } - if(buffer[0] != LSM6DS3_ACCEL_CHIP_ID){ + if(buffer[0] != LSM6DS3_ACCEL_CHIP_ID && buffer[0] != LSM6DS3TRC_ACCEL_CHIP_ID) { LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], LSM6DS3_ACCEL_CHIP_ID); ret = -1; goto fail; } + if (buffer[0] == LSM6DS3TRC_ACCEL_CHIP_ID) { + source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; + } + // TODO: set scale and bandwith. Default is +- 2G, 50 Hz ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ); - if (ret < 0){ + if (ret < 0) { goto fail; } @@ -34,7 +38,7 @@ fail: return ret; } -void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event){ +void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; @@ -46,7 +50,7 @@ void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event){ float y = read_16_bit(buffer[2], buffer[3]) * scale; float z = read_16_bit(buffer[4], buffer[5]) * scale; - event.setSource(cereal::SensorEventData::SensorSource::LSM6DS3); + event.setSource(source); event.setVersion(1); event.setSensor(SENSOR_ACCELEROMETER); event.setType(SENSOR_TYPE_ACCELEROMETER); diff --git a/selfdrive/sensord/sensors/lsm6ds3_accel.h b/selfdrive/sensord/sensors/lsm6ds3_accel.h index e5a949d4f..4a6b68744 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_accel.h +++ b/selfdrive/sensord/sensors/lsm6ds3_accel.h @@ -12,11 +12,13 @@ // Constants #define LSM6DS3_ACCEL_CHIP_ID 0x69 +#define LSM6DS3TRC_ACCEL_CHIP_ID 0x6A #define LSM6DS3_ACCEL_ODR_104HZ (0b0100 << 4) class LSM6DS3_Accel : public I2CSensor { uint8_t get_device_address() {return LSM6DS3_ACCEL_I2C_ADDR;} + cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; public: LSM6DS3_Accel(I2CBus *bus); int init(); diff --git a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc index ae651f2cb..6732ead0f 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc @@ -11,25 +11,29 @@ LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus) : I2CSensor(bus) {} -int LSM6DS3_Gyro::init(){ +int LSM6DS3_Gyro::init() { int ret = 0; uint8_t buffer[1]; ret = read_register(LSM6DS3_GYRO_I2C_REG_ID, buffer, 1); - if(ret < 0){ + if(ret < 0) { LOGE("Reading chip ID failed: %d", ret); goto fail; } - if(buffer[0] != LSM6DS3_GYRO_CHIP_ID){ + if(buffer[0] != LSM6DS3_GYRO_CHIP_ID && buffer[0] != LSM6DS3TRC_GYRO_CHIP_ID) { LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], LSM6DS3_GYRO_CHIP_ID); ret = -1; goto fail; } + if (buffer[0] == LSM6DS3TRC_GYRO_CHIP_ID) { + source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; + } + // TODO: set scale. Default is +- 250 deg/s ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_104HZ); - if (ret < 0){ + if (ret < 0) { goto fail; } @@ -38,7 +42,7 @@ fail: return ret; } -void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event){ +void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[6]; @@ -50,7 +54,7 @@ void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event){ float y = DEG2RAD(read_16_bit(buffer[2], buffer[3]) * scale); float z = DEG2RAD(read_16_bit(buffer[4], buffer[5]) * scale); - event.setSource(cereal::SensorEventData::SensorSource::LSM6DS3); + event.setSource(source); event.setVersion(2); event.setSensor(SENSOR_GYRO_UNCALIBRATED); event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED); diff --git a/selfdrive/sensord/sensors/lsm6ds3_gyro.h b/selfdrive/sensord/sensors/lsm6ds3_gyro.h index cb8595e76..d7e8f0025 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_gyro.h +++ b/selfdrive/sensord/sensors/lsm6ds3_gyro.h @@ -12,11 +12,13 @@ // Constants #define LSM6DS3_GYRO_CHIP_ID 0x69 +#define LSM6DS3TRC_GYRO_CHIP_ID 0x6A #define LSM6DS3_GYRO_ODR_104HZ (0b0100 << 4) class LSM6DS3_Gyro : public I2CSensor { uint8_t get_device_address() {return LSM6DS3_GYRO_I2C_ADDR;} + cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; public: LSM6DS3_Gyro(I2CBus *bus); int init(); diff --git a/selfdrive/sensord/sensors/lsm6ds3_temp.cc b/selfdrive/sensord/sensors/lsm6ds3_temp.cc index 3b9e90f5e..6b093fce0 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_temp.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_temp.cc @@ -7,36 +7,41 @@ LSM6DS3_Temp::LSM6DS3_Temp(I2CBus *bus) : I2CSensor(bus) {} -int LSM6DS3_Temp::init(){ +int LSM6DS3_Temp::init() { int ret = 0; uint8_t buffer[1]; ret = read_register(LSM6DS3_TEMP_I2C_REG_ID, buffer, 1); - if(ret < 0){ + if(ret < 0) { LOGE("Reading chip ID failed: %d", ret); goto fail; } - if(buffer[0] != LSM6DS3_TEMP_CHIP_ID){ + if(buffer[0] != LSM6DS3_TEMP_CHIP_ID && buffer[0] != LSM6DS3TRC_TEMP_CHIP_ID) { LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], LSM6DS3_TEMP_CHIP_ID); ret = -1; goto fail; } + if (buffer[0] == LSM6DS3TRC_TEMP_CHIP_ID) { + source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; + } + fail: return ret; } -void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event){ +void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) { uint64_t start_time = nanos_since_boot(); uint8_t buffer[2]; int len = read_register(LSM6DS3_TEMP_I2C_REG_OUT_TEMP_L, buffer, sizeof(buffer)); assert(len == sizeof(buffer)); - float temp = 25.0f + read_16_bit(buffer[0], buffer[1]) / 16.0f; + float scale = (source == cereal::SensorEventData::SensorSource::LSM6DS3TRC) ? 256.0f : 16.0f; + float temp = 25.0f + read_16_bit(buffer[0], buffer[1]) / scale; - event.setSource(cereal::SensorEventData::SensorSource::LSM6DS3); + event.setSource(source); event.setVersion(1); event.setType(SENSOR_TYPE_AMBIENT_TEMPERATURE); event.setTimestamp(start_time); diff --git a/selfdrive/sensord/sensors/lsm6ds3_temp.h b/selfdrive/sensord/sensors/lsm6ds3_temp.h index c556631de..8188f4670 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_temp.h +++ b/selfdrive/sensord/sensors/lsm6ds3_temp.h @@ -11,10 +11,13 @@ // Constants #define LSM6DS3_TEMP_CHIP_ID 0x69 +#define LSM6DS3TRC_TEMP_CHIP_ID 0x6A class LSM6DS3_Temp : public I2CSensor { uint8_t get_device_address() {return LSM6DS3_TEMP_I2C_ADDR;} + cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; + public: LSM6DS3_Temp(I2CBus *bus); int init(); diff --git a/selfdrive/sensord/sensors/mmc5603nj_magn.cc b/selfdrive/sensord/sensors/mmc5603nj_magn.cc new file mode 100644 index 000000000..829a7f7d2 --- /dev/null +++ b/selfdrive/sensord/sensors/mmc5603nj_magn.cc @@ -0,0 +1,77 @@ +#include "mmc5603nj_magn.h" + +#include + +#include "selfdrive/common/swaglog.h" +#include "selfdrive/common/timing.h" + +MMC5603NJ_Magn::MMC5603NJ_Magn(I2CBus *bus) : I2CSensor(bus) {} + +int MMC5603NJ_Magn::init() { + int ret = 0; + uint8_t buffer[1]; + + ret = read_register(MMC5603NJ_I2C_REG_ID, buffer, 1); + if(ret < 0) { + LOGE("Reading chip ID failed: %d", ret); + goto fail; + } + + if(buffer[0] != MMC5603NJ_CHIP_ID) { + LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], MMC5603NJ_CHIP_ID); + ret = -1; + goto fail; + } + + // Set 100 Hz + ret = set_register(MMC5603NJ_I2C_REG_ODR, 100); + if (ret < 0) { + goto fail; + } + + // Set BW to 0b01 for 1-150 Hz operation + ret = set_register(MMC5603NJ_I2C_REG_INTERNAL_1, 0b01); + if (ret < 0) { + goto fail; + } + + // Set compute measurement rate + ret = set_register(MMC5603NJ_I2C_REG_INTERNAL_0, MMC5603NJ_CMM_FREQ_EN | MMC5603NJ_AUTO_SR_EN); + if (ret < 0) { + goto fail; + } + + // Enable continous mode, set every 100 measurements + ret = set_register(MMC5603NJ_I2C_REG_INTERNAL_2, MMC5603NJ_CMM_EN | MMC5603NJ_EN_PRD_SET | 0b11); + if (ret < 0) { + goto fail; + } + +fail: + return ret; +} + +void MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) { + + uint64_t start_time = nanos_since_boot(); + uint8_t buffer[9]; + int len = read_register(MMC5603NJ_I2C_REG_XOUT0, buffer, sizeof(buffer)); + assert(len == sizeof(buffer)); + + float scale = 1.0 / 16384.0; + float x = read_20_bit(buffer[6], buffer[1], buffer[0]) * scale; + float y = read_20_bit(buffer[7], buffer[3], buffer[2]) * scale; + float z = read_20_bit(buffer[8], buffer[5], buffer[4]) * scale; + + event.setSource(cereal::SensorEventData::SensorSource::MMC5603NJ); + event.setVersion(1); + event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); + event.setType(SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED); + event.setTimestamp(start_time); + + float xyz[] = {x, y, z}; + auto svec = event.initMagneticUncalibrated(); + svec.setV(xyz); + svec.setStatus(true); + +} diff --git a/selfdrive/sensord/sensors/mmc5603nj_magn.h b/selfdrive/sensord/sensors/mmc5603nj_magn.h new file mode 100644 index 000000000..58840bbf2 --- /dev/null +++ b/selfdrive/sensord/sensors/mmc5603nj_magn.h @@ -0,0 +1,29 @@ +#pragma once + +#include "selfdrive/sensord/sensors/i2c_sensor.h" + +// Address of the chip on the bus +#define MMC5603NJ_I2C_ADDR 0x30 + +// Registers of the chip +#define MMC5603NJ_I2C_REG_XOUT0 0x00 +#define MMC5603NJ_I2C_REG_ODR 0x1A +#define MMC5603NJ_I2C_REG_INTERNAL_0 0x1B +#define MMC5603NJ_I2C_REG_INTERNAL_1 0x1C +#define MMC5603NJ_I2C_REG_INTERNAL_2 0x1D +#define MMC5603NJ_I2C_REG_ID 0x39 + +// Constants +#define MMC5603NJ_CHIP_ID 0x10 +#define MMC5603NJ_CMM_FREQ_EN (1 << 7) +#define MMC5603NJ_AUTO_SR_EN (1 << 5) +#define MMC5603NJ_CMM_EN (1 << 4) +#define MMC5603NJ_EN_PRD_SET (1 << 3) + +class MMC5603NJ_Magn : public I2CSensor { + uint8_t get_device_address() {return MMC5603NJ_I2C_ADDR;} +public: + MMC5603NJ_Magn(I2CBus *bus); + int init(); + void get_event(cereal::SensorEventData::Builder &event); +}; diff --git a/selfdrive/sensord/sensors_qcom.cc b/selfdrive/sensord/sensors_qcom.cc index 81bb78e85..fcdb9a72d 100644 --- a/selfdrive/sensord/sensors_qcom.cc +++ b/selfdrive/sensord/sensors_qcom.cc @@ -1,10 +1,5 @@ -#include #include #include -#include -#include -#include -#include #include #include #include @@ -12,6 +7,11 @@ #include #include +#include +#include +#include +#include +#include #include #include @@ -189,7 +189,7 @@ void sensor_loop() { pm.send("sensorEvents", msg); - if (re_init_sensors){ + if (re_init_sensors) { LOGE("Resetting sensors"); re_init_sensors = false; break; diff --git a/selfdrive/sensord/sensors_qcom2.cc b/selfdrive/sensord/sensors_qcom2.cc index d0f8cf00e..36526df0f 100644 --- a/selfdrive/sensord/sensors_qcom2.cc +++ b/selfdrive/sensord/sensors_qcom2.cc @@ -18,6 +18,7 @@ #include "selfdrive/sensord/sensors/lsm6ds3_accel.h" #include "selfdrive/sensord/sensors/lsm6ds3_gyro.h" #include "selfdrive/sensord/sensors/lsm6ds3_temp.h" +#include "selfdrive/sensord/sensors/mmc5603nj_magn.h" #include "selfdrive/sensord/sensors/sensor.h" #define I2C_BUS_IMU 1 @@ -43,40 +44,51 @@ int sensor_loop() { LSM6DS3_Gyro lsm6ds3_gyro(i2c_bus_imu); LSM6DS3_Temp lsm6ds3_temp(i2c_bus_imu); + MMC5603NJ_Magn mmc5603nj_magn(i2c_bus_imu); + LightSensor light("/sys/class/i2c-adapter/i2c-2/2-0038/iio:device1/in_intensity_both_raw"); // Sensor init + std::vector> sensors_init; // Sensor, required + sensors_init.push_back({&bmx055_accel, true}); + sensors_init.push_back({&bmx055_gyro, true}); + sensors_init.push_back({&bmx055_magn, true}); + sensors_init.push_back({&bmx055_temp, true}); + + sensors_init.push_back({&lsm6ds3_accel, true}); + sensors_init.push_back({&lsm6ds3_gyro, true}); + sensors_init.push_back({&lsm6ds3_temp, true}); + + sensors_init.push_back({&mmc5603nj_magn, false}); + + sensors_init.push_back({&light, true}); + + + // Initialize sensors std::vector sensors; - sensors.push_back(&bmx055_accel); - sensors.push_back(&bmx055_gyro); - sensors.push_back(&bmx055_magn); - sensors.push_back(&bmx055_temp); - - sensors.push_back(&lsm6ds3_accel); - sensors.push_back(&lsm6ds3_gyro); - sensors.push_back(&lsm6ds3_temp); - - sensors.push_back(&light); - - - for (Sensor * sensor : sensors){ - int err = sensor->init(); - if (err < 0){ - LOGE("Error initializing sensors"); - return -1; + for (auto &sensor : sensors_init) { + int err = sensor.first->init(); + if (err < 0) { + // Fail on required sensors + if (sensor.second) { + LOGE("Error initializing sensors"); + return -1; + } + } else { + sensors.push_back(sensor.first); } } PubMaster pm({"sensorEvents"}); - while (!do_exit){ + while (!do_exit) { std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); const int num_events = sensors.size(); MessageBuilder msg; auto sensor_events = msg.initEvent().initSensorEvents(num_events); - for (int i = 0; i < num_events; i++){ + for (int i = 0; i < num_events; i++) { auto event = sensor_events[i]; sensors[i]->get_event(event); } diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index d186f8c05..53c7b3909 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -1,6 +1,9 @@ #!/usr/bin/bash -e -export SOURCE_DIR="/data/openpilot_source/" +if [ -z "$SOURCE_DIR" ]; then + echo "SOURCE_DIR must be set" + exit 1 +fi if [ -z "$GIT_COMMIT" ]; then echo "GIT_COMMIT must be set" @@ -12,19 +15,8 @@ if [ -z "$TEST_DIR" ]; then exit 1 fi -# setup jenkins device -if [ ! -d "$SOURCE_DIR" ]; then - # write continue.sh - CONTINUE_FILE="/data/data/com.termux/files/continue.sh" - echo "#!/usr/bin/bash" > $CONTINUE_FILE - echo "wpa_cli IFNAME=wlan0 SCAN" >> $CONTINUE_FILE - echo "sleep infinity" >> $CONTINUE_FILE - - # write SSH keys - curl "https://github.com/commaci2.keys" > /data/params/d/GithubSshKeys - - git clone --depth 1 https://github.com/commaai/openpilot.git "$SOURCE_DIR" -fi +umount /data/safe_staging/merged/ || true +sudo umount /data/safe_staging/merged/ || true if [ -f "/EON" ]; then rm -rf /data/core @@ -37,14 +29,15 @@ cd $SOURCE_DIR git reset --hard git fetch find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \; +git fetch --verbose origin $GIT_COMMIT git reset --hard $GIT_COMMIT git checkout $GIT_COMMIT git clean -xdf git submodule update --init --recursive -git submodule foreach --recursive git reset --hard -git submodule foreach --recursive git clean -xdf -echo "git checkout took $SECONDS seconds" +git submodule foreach --recursive "git reset --hard && git clean -xdf" + +echo "git checkout done, t=$SECONDS" rsync -a --delete $SOURCE_DIR $TEST_DIR -echo "$TEST_DIR synced with $GIT_COMMIT, took $SECONDS seconds" +echo "$TEST_DIR synced with $GIT_COMMIT, t=$SECONDS" diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index c152fc864..7bd228fc7 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -154,7 +154,8 @@ class TestOnroad(unittest.TestCase): self.assertTrue(cpu_ok) def test_model_timings(self): - cfgs = [("modelV2", 0.035, 0.03), ("driverState", 0.022, 0.018)] + #TODO this went up when plannerd cpu usage increased, why? + cfgs = [("modelV2", 0.035, 0.03), ("driverState", 0.025, 0.021)] for (s, instant_max, avg_max) in cfgs: ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.lr if m.which() == s] self.assertLess(min(ts), instant_max, f"high '{s}' execution time: {min(ts)}") diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 950b34e8b..9256d0345 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -156,6 +156,8 @@ def thermald_thread(): network_type = NetworkType.none network_strength = NetworkStrength.unknown network_info = None + modem_version = None + registered_count = 0 current_filter = FirstOrderFilter(0., CURRENT_TAU, DT_TRML) cpu_temp_filter = FirstOrderFilter(0., CPU_TEMP_TAU, DT_TRML) @@ -169,6 +171,7 @@ def thermald_thread(): power_monitor = PowerMonitoring() no_panda_cnt = 0 + HARDWARE.initialize_hardware() thermal_config = HARDWARE.get_thermal_config() if params.get_bool("IsOnroad"): @@ -235,12 +238,30 @@ def thermald_thread(): network_type = HARDWARE.get_network_type() network_strength = HARDWARE.get_network_strength(network_type) network_info = HARDWARE.get_network_info() # pylint: disable=assignment-from-none + + # Log modem version once + if modem_version is None: + modem_version = HARDWARE.get_modem_version() # pylint: disable=assignment-from-none + if modem_version is not None: + cloudlog.warning(f"Modem version: {modem_version}") + + if TICI and (network_info.get('state', None) == "REGISTERED"): + registered_count += 1 + else: + registered_count = 0 + + if registered_count > 10: + cloudlog.warning(f"Modem stuck in registered state {network_info}. nmcli conn up lte") + os.system("nmcli conn up lte") + registered_count = 0 + except Exception: cloudlog.exception("Error getting network status") msg.deviceState.freeSpacePercent = get_available_percent(default=100.0) msg.deviceState.memoryUsagePercent = int(round(psutil.virtual_memory().percent)) msg.deviceState.cpuUsagePercent = int(round(psutil.cpu_percent())) + msg.deviceState.gpuUsagePercent = int(round(HARDWARE.get_gpu_usage_percent())) msg.deviceState.networkType = network_type msg.deviceState.networkStrength = network_strength if network_info is not None: @@ -345,7 +366,7 @@ def thermald_thread(): # with 2% left, we killall, otherwise the phone will take a long time to boot startup_conditions["free_space"] = msg.deviceState.freeSpacePercent > 2 startup_conditions["completed_training"] = params.get("CompletedTrainingVersion") == training_version or \ - (current_branch in ['dashcam', 'dashcam-staging']) + params.get_bool("Passive") startup_conditions["not_driver_view"] = not params.get_bool("IsDriverViewEnabled") startup_conditions["not_taking_snapshot"] = not params.get_bool("IsTakingSnapshot") # if any CPU gets above 107 or the battery gets above 63, kill all processes @@ -362,9 +383,6 @@ def thermald_thread(): params.put_bool("IsOnroad", should_start) params.put_bool("IsOffroad", not should_start) HARDWARE.set_power_save(not should_start) - if TICI and not params.get_bool("EnableLteOnroad"): - fxn = "off" if should_start else "on" - os.system(f"nmcli radio wwan {fxn}") if should_start: off_ts = None diff --git a/selfdrive/ui/.gitignore b/selfdrive/ui/.gitignore index 2dbc32523..3f5116f24 100644 --- a/selfdrive/ui/.gitignore +++ b/selfdrive/ui/.gitignore @@ -7,4 +7,4 @@ qt/spinner qt/setup/setup qt/setup/reset qt/setup/wifi -qt/setup/installer* +qt/setup/installer_* diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index d7625cf1c..df607ec7f 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -19,7 +19,8 @@ if arch == "Darwin": del base_libs[base_libs.index('OpenCL')] qt_env['FRAMEWORKS'] += ['OpenCL'] -widgets_src = ["qt/widgets/input.cc", "qt/widgets/drive_stats.cc", +widgets_src = ["qt/util.cc", + "qt/widgets/input.cc", "qt/widgets/drive_stats.cc", "qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc", "qt/widgets/offroad_alerts.cc", "qt/widgets/setup.cc", "qt/widgets/keyboard.cc", "qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#phonelibs/qrcode/QrCode.cc", "qt/api.cc", @@ -30,7 +31,7 @@ if arch != 'aarch64': if maps: base_libs += ['qmapboxgl'] - widgets_src += ["qt/maps/map_helpers.cc", "qt/maps/map.cc"] + widgets_src += ["qt/maps/map_helpers.cc", "qt/maps/map_settings.cc", "qt/maps/map.cc"] qt_env['CPPDEFINES'] = ["ENABLE_MAPS"] widgets = qt_env.Library("qt_widgets", widgets_src, LIBS=base_libs) @@ -38,7 +39,7 @@ qt_libs = [widgets] + base_libs # spinner and text window qt_env.Program("qt/text", ["qt/text.cc"], LIBS=qt_libs) -qt_env.Program("qt/spinner", ["qt/spinner.cc"], LIBS=base_libs) +qt_env.Program("qt/spinner", ["qt/spinner.cc"], LIBS=qt_libs) # build main UI qt_src = ["main.cc", "ui.cc", "paint.cc", "qt/sidebar.cc", "qt/onroad.cc", @@ -48,13 +49,15 @@ qt_src = ["main.cc", "ui.cc", "paint.cc", "qt/sidebar.cc", "qt/onroad.cc", qt_env.Program("_ui", qt_src, LIBS=qt_libs) # setup, factory resetter, and installer -if arch != 'aarch64' and "BUILD_SETUP" in os.environ: +if arch != 'aarch64' and GetOption('setup'): qt_env.Program("qt/setup/reset", ["qt/setup/reset.cc"], LIBS=qt_libs) qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc"], LIBS=qt_libs + ['curl', 'common', 'json11']) qt_env.Program("qt/setup/wifi", ["qt/setup/wifi.cc"], LIBS=qt_libs + ['common', 'json11']) + senv = qt_env.Clone() + senv['LINKFLAGS'].append('-Wl,-strip-debug') installers = [ - ("openpilot", "master"), + ("openpilot", "release3-staging"), ("openpilot_test", "release3-staging"), ("openpilot_internal", "master"), ("dashcam", "dashcam3-staging"), @@ -69,8 +72,11 @@ if arch != 'aarch64' and "BUILD_SETUP" in os.environ: r = requests.get("https://github.com/commaci2.keys") r.raise_for_status() d['SSH_KEYS'] = f'\\"{r.text.strip()}\\"' - obj = qt_env.Object(f"qt/setup/installer_{name}.o", ["qt/setup/installer.cc"], CPPDEFINES=d) - qt_env.Program(f"qt/setup/installer_{name}", obj, LIBS=qt_libs, CPPDEFINES=d) + obj = senv.Object(f"qt/setup/installer_{name}.o", ["qt/setup/installer.cc"], CPPDEFINES=d) + f = senv.Program(f"qt/setup/installer_{name}", obj, LIBS=qt_libs) + # keep installers small + assert f[0].get_size() < 300*1e3 + # build headless replay if arch == 'x86_64' and os.path.exists(Dir("#tools/").get_abspath()): diff --git a/selfdrive/ui/main.cc b/selfdrive/ui/main.cc index dab8d6654..63bbffa7a 100644 --- a/selfdrive/ui/main.cc +++ b/selfdrive/ui/main.cc @@ -3,21 +3,14 @@ #include "selfdrive/hardware/hw.h" #include "selfdrive/ui/qt/qt_window.h" +#include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/window.h" int main(int argc, char *argv[]) { - QSurfaceFormat fmt; -#ifdef __APPLE__ - fmt.setVersion(3, 2); - fmt.setProfile(QSurfaceFormat::OpenGLContextProfile::CoreProfile); - fmt.setRenderableType(QSurfaceFormat::OpenGL); -#else - fmt.setRenderableType(QSurfaceFormat::OpenGLES); -#endif - QSurfaceFormat::setDefaultFormat(fmt); + qInstallMessageHandler(swagLogMessageHandler); + initApp(); if (Hardware::EON()) { - QApplication::setAttribute(Qt::AA_ShareOpenGLContexts); QSslConfiguration ssl = QSslConfiguration::defaultConfiguration(); ssl.setCaCertificates(QSslCertificate::fromPath("/usr/etc/tls/cert.pem")); QSslConfiguration::setDefaultConfiguration(ssl); diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index eb834ef9f..96d635ac9 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -1,8 +1,7 @@ -#include "paint.h" - -#include +#include "selfdrive/ui/paint.h" #include +#include #ifdef __APPLE__ #include @@ -85,7 +84,7 @@ static void draw_lead(UIState *s, const cereal::RadarState::LeadData::Reader &le fillAlpha = (int)(fmin(fillAlpha, 255)); } - float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; + float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35; x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); y = std::fmin(s->viz_rect.bottom() - sz * .6, y); draw_chevron(s, x, y, sz, nvgRGBA(201, 34, 49, fillAlpha), COLOR_YELLOW); @@ -435,21 +434,21 @@ void ui_nvg_init(UIState *s) { ui_resize(s, s->fb_w, s->fb_h); } -void ui_resize(UIState *s, int width, int height){ +void ui_resize(UIState *s, int width, int height) { s->fb_w = width; s->fb_h = height; auto intrinsic_matrix = s->wide_camera ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; - s->zoom = zoom / intrinsic_matrix.v[0]; + float zoom = ZOOM / intrinsic_matrix.v[0]; if (s->wide_camera) { - s->zoom *= 0.5; + zoom *= 0.5; } s->video_rect = Rect{bdr_s, bdr_s, s->fb_w - 2 * bdr_s, s->fb_h - 2 * bdr_s}; - float zx = s->zoom * 2 * intrinsic_matrix.v[2] / s->video_rect.w; - float zy = s->zoom * 2 * intrinsic_matrix.v[5] / s->video_rect.h; + float zx = zoom * 2 * intrinsic_matrix.v[2] / s->video_rect.w; + float zy = zoom * 2 * intrinsic_matrix.v[5] / s->video_rect.h; const mat4 frame_transform = {{ zx, 0.0, 0.0, 0.0, @@ -465,7 +464,7 @@ void ui_resize(UIState *s, int width, int height){ nvgTranslate(s->vg, s->video_rect.x + s->video_rect.w / 2, s->video_rect.y + s->video_rect.h / 2 + y_offset); // 2) Apply same scaling as video - nvgScale(s->vg, s->zoom, s->zoom); + nvgScale(s->vg, zoom, zoom); // 3) Put (0, 0) in top left corner of video nvgTranslate(s->vg, -intrinsic_matrix.v[2], -intrinsic_matrix.v[5]); diff --git a/selfdrive/ui/qt/api.cc b/selfdrive/ui/qt/api.cc index 771af0fcf..e604a5c09 100644 --- a/selfdrive/ui/qt/api.cc +++ b/selfdrive/ui/qt/api.cc @@ -1,26 +1,27 @@ #include "selfdrive/ui/qt/api.h" +#include +#include +#include + +#include #include #include #include #include -#include -#include #include -#include -#include -#include -#include #include "selfdrive/common/params.h" #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" +namespace CommaApi { + const std::string private_key_path = Hardware::PC() ? util::getenv_default("HOME", "/.comma/persist/comma/id_rsa", "/persist/comma/id_rsa") : "/persist/comma/id_rsa"; -QByteArray CommaApi::rsa_sign(const QByteArray &data) { +QByteArray rsa_sign(const QByteArray &data) { auto file = QFile(private_key_path.c_str()); if (!file.open(QIODevice::ReadOnly)) { qDebug() << "No RSA private key found, please run manager.py or registration.py"; @@ -44,21 +45,14 @@ QByteArray CommaApi::rsa_sign(const QByteArray &data) { return sig; } -QString CommaApi::create_jwt(const QVector> &payloads, int expiry) { +QString create_jwt(const QJsonObject &payloads, int expiry) { + QJsonObject header = {{"alg", "RS256"}}; + QString dongle_id = QString::fromStdString(Params().get("DongleId")); - - QJsonObject header; - header.insert("alg", "RS256"); - - QJsonObject payload; - payload.insert("identity", dongle_id); - auto t = QDateTime::currentSecsSinceEpoch(); - payload.insert("nbf", t); - payload.insert("iat", t); - payload.insert("exp", t + expiry); - for (auto &load : payloads) { - payload.insert(load.first, load.second); + QJsonObject payload = {{"identity", dongle_id}, {"nbf", t}, {"iat", t}, {"exp", t + expiry}}; + for (auto it = payloads.begin(); it != payloads.end(); ++it) { + payload.insert(it.key(), it.value()); } auto b64_opts = QByteArray::Base64UrlEncoding | QByteArray::OmitTrailingEquals; @@ -71,8 +65,9 @@ QString CommaApi::create_jwt(const QVector> &payloads return jwt; } +} // namespace CommaApi -HttpRequest::HttpRequest(QObject *parent, const QString &requestURL, const QString &cache_key, bool create_jwt_) : cache_key(cache_key), create_jwt(create_jwt_), QObject(parent) { +HttpRequest::HttpRequest(QObject *parent, const QString &requestURL, bool create_jwt_) : create_jwt(create_jwt_), QObject(parent) { networkAccessManager = new QNetworkAccessManager(this); reply = NULL; @@ -82,15 +77,9 @@ HttpRequest::HttpRequest(QObject *parent, const QString &requestURL, const QStri connect(networkTimer, &QTimer::timeout, this, &HttpRequest::requestTimeout); sendRequest(requestURL); - - if (!cache_key.isEmpty()) { - if (std::string cached_resp = Params().get(cache_key.toStdString()); !cached_resp.empty()) { - QTimer::singleShot(0, [=]() { emit receivedResponse(QString::fromStdString(cached_resp)); }); - } - } } -void HttpRequest::sendRequest(const QString &requestURL){ +void HttpRequest::sendRequest(const QString &requestURL) { QString token; if(create_jwt) { token = CommaApi::create_jwt(); @@ -110,26 +99,19 @@ void HttpRequest::sendRequest(const QString &requestURL){ connect(reply, &QNetworkReply::finished, this, &HttpRequest::requestFinished); } -void HttpRequest::requestTimeout(){ +void HttpRequest::requestTimeout() { reply->abort(); } // This function should always emit something -void HttpRequest::requestFinished(){ +void HttpRequest::requestFinished() { if (reply->error() != QNetworkReply::OperationCanceledError) { networkTimer->stop(); QString response = reply->readAll(); if (reply->error() == QNetworkReply::NoError) { - // save to cache - if (!cache_key.isEmpty()) { - Params().put(cache_key.toStdString(), response.toStdString()); - } emit receivedResponse(response); } else { - if (!cache_key.isEmpty()) { - Params().remove(cache_key.toStdString()); - } qDebug() << reply->errorString(); emit failedResponse(reply->errorString()); } diff --git a/selfdrive/ui/qt/api.h b/selfdrive/ui/qt/api.h index 71fd9b868..8aa01ae2b 100644 --- a/selfdrive/ui/qt/api.h +++ b/selfdrive/ui/qt/api.h @@ -1,26 +1,16 @@ #pragma once -#include -#include -#include - -#include -#include +#include #include -#include -#include #include -#include -#include -#include +#include -class CommaApi : public QObject { - Q_OBJECT +namespace CommaApi { -public: - static QByteArray rsa_sign(const QByteArray &data); - static QString create_jwt(const QVector> &payloads = {}, int expiry = 3600); -}; +QByteArray rsa_sign(const QByteArray &data); +QString create_jwt(const QJsonObject &payloads = {}, int expiry = 3600); + +} // namespace CommaApi /** * Makes a request to the request endpoint. @@ -30,14 +20,15 @@ class HttpRequest : public QObject { Q_OBJECT public: - explicit HttpRequest(QObject* parent, const QString &requestURL, const QString &cache_key = "", bool create_jwt_ = true); - QNetworkReply *reply; + explicit HttpRequest(QObject* parent, const QString &requestURL, bool create_jwt_ = true); void sendRequest(const QString &requestURL); +protected: + QNetworkReply *reply; + private: QNetworkAccessManager *networkAccessManager; QTimer *networkTimer; - QString cache_key; bool create_jwt; private slots: diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index bdda7f91b..4800fc5c5 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -6,26 +6,27 @@ #include #include "selfdrive/common/params.h" -#include "selfdrive/common/swaglog.h" -#include "selfdrive/common/timing.h" -#include "selfdrive/common/util.h" +#include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/drive_stats.h" #include "selfdrive/ui/qt/widgets/setup.h" // HomeWindow: the container for the offroad and onroad UIs HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { - QHBoxLayout *layout = new QHBoxLayout(this); - layout->setMargin(0); - layout->setSpacing(0); + QHBoxLayout *main_layout = new QHBoxLayout(this); + main_layout->setMargin(0); + main_layout->setSpacing(0); sidebar = new Sidebar(this); - layout->addWidget(sidebar); + main_layout->addWidget(sidebar); QObject::connect(this, &HomeWindow::update, sidebar, &Sidebar::updateState); QObject::connect(sidebar, &Sidebar::openSettings, this, &HomeWindow::openSettings); slayout = new QStackedLayout(); - layout->addLayout(slayout); + main_layout->addLayout(slayout); + + home = new OffroadHome(); + slayout->addWidget(home); onroad = new OnroadWindow(this); slayout->addWidget(onroad); @@ -33,17 +34,15 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { QObject::connect(this, &HomeWindow::update, onroad, &OnroadWindow::update); QObject::connect(this, &HomeWindow::offroadTransitionSignal, onroad, &OnroadWindow::offroadTransitionSignal); - home = new OffroadHome(); - slayout->addWidget(home); - QObject::connect(this, &HomeWindow::openSettings, home, &OffroadHome::refresh); - driver_view = new DriverViewWindow(this); connect(driver_view, &DriverViewWindow::done, [=] { showDriverView(false); }); slayout->addWidget(driver_view); +} - setLayout(layout); +void HomeWindow::showSidebar(bool show) { + sidebar->setVisible(show); } void HomeWindow::offroadTransition(bool offroad) { @@ -72,7 +71,7 @@ void HomeWindow::mousePressEvent(QMouseEvent* e) { // TODO: Handle this without exposing pointer to map widget // Hide map first if visible, then hide sidebar - if (onroad->map != nullptr && onroad->map->isVisible()){ + if (onroad->map != nullptr && onroad->map->isVisible()) { onroad->map->setVisible(false); } else if (!sidebar->isVisible()) { sidebar->setVisible(true); @@ -87,25 +86,29 @@ void HomeWindow::mousePressEvent(QMouseEvent* e) { // OffroadHome: the offroad home page OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { - QVBoxLayout* main_layout = new QVBoxLayout(); + QVBoxLayout* main_layout = new QVBoxLayout(this); main_layout->setMargin(50); // top header QHBoxLayout* header_layout = new QHBoxLayout(); + header_layout->setSpacing(16); date = new QLabel(); - date->setStyleSheet(R"(font-size: 55px;)"); - header_layout->addWidget(date, 0, Qt::AlignHCenter | Qt::AlignLeft); + header_layout->addWidget(date, 1, Qt::AlignHCenter | Qt::AlignLeft); - alert_notification = new QPushButton(); - alert_notification->setVisible(false); - QObject::connect(alert_notification, &QPushButton::released, this, &OffroadHome::openAlerts); - header_layout->addWidget(alert_notification, 0, Qt::AlignHCenter | Qt::AlignRight); + update_notif = new QPushButton("UPDATE"); + update_notif->setVisible(false); + update_notif->setStyleSheet("background-color: #364DEF;"); + QObject::connect(update_notif, &QPushButton::released, [=]() { center_layout->setCurrentIndex(1); }); + header_layout->addWidget(update_notif, 0, Qt::AlignHCenter | Qt::AlignRight); - std::string brand = Params().getBool("Passive") ? "dashcam" : "openpilot"; - QLabel* version = new QLabel(QString::fromStdString(brand + " v" + Params().get("Version"))); - version->setStyleSheet(R"(font-size: 55px;)"); - header_layout->addWidget(version, 0, Qt::AlignHCenter | Qt::AlignRight); + alert_notif = new QPushButton(); + alert_notif->setVisible(false); + alert_notif->setStyleSheet("background-color: #E22C2C;"); + QObject::connect(alert_notif, &QPushButton::released, [=] { center_layout->setCurrentIndex(2); }); + header_layout->addWidget(alert_notif, 0, Qt::AlignHCenter | Qt::AlignRight); + + header_layout->addWidget(new QLabel(getBrandVersion()), 0, Qt::AlignHCenter | Qt::AlignRight); main_layout->addLayout(header_layout); @@ -113,98 +116,78 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { main_layout->addSpacing(25); center_layout = new QStackedLayout(); - QHBoxLayout* statsAndSetup = new QHBoxLayout(); + QWidget* statsAndSetupWidget = new QWidget(this); + QHBoxLayout* statsAndSetup = new QHBoxLayout(statsAndSetupWidget); statsAndSetup->setMargin(0); - - DriveStats* drive = new DriveStats; + DriveStats* drive = new DriveStats(); drive->setFixedSize(800, 800); statsAndSetup->addWidget(drive); - - SetupWidget* setup = new SetupWidget; - statsAndSetup->addWidget(setup); - - QWidget* statsAndSetupWidget = new QWidget(); - statsAndSetupWidget->setLayout(statsAndSetup); + statsAndSetup->addWidget(new SetupWidget); center_layout->addWidget(statsAndSetupWidget); + // add update & alerts widgets + update_widget = new UpdateAlert(); + QObject::connect(update_widget, &UpdateAlert::dismiss, [=]() { center_layout->setCurrentIndex(0); }); + center_layout->addWidget(update_widget); alerts_widget = new OffroadAlert(); - QObject::connect(alerts_widget, &OffroadAlert::closeAlerts, this, &OffroadHome::closeAlerts); + QObject::connect(alerts_widget, &OffroadAlert::dismiss, [=]() { center_layout->setCurrentIndex(0); }); center_layout->addWidget(alerts_widget); - center_layout->setAlignment(alerts_widget, Qt::AlignCenter); main_layout->addLayout(center_layout, 1); // set up refresh timer timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, this, &OffroadHome::refresh); - timer->start(10 * 1000); + timer->callOnTimeout(this, &OffroadHome::refresh); - setLayout(main_layout); setStyleSheet(R"( - OffroadHome { - background-color: black; - } * { color: white; } + OffroadHome { + background-color: black; + } + OffroadHome > QPushButton { + padding: 15px 30px; + border-radius: 5px; + font-size: 40px; + font-weight: 500; + } + OffroadHome > QLabel { + font-size: 55px; + } )"); -} - -void OffroadHome::showEvent(QShowEvent *event) { refresh(); } -void OffroadHome::openAlerts() { - center_layout->setCurrentIndex(1); +void OffroadHome::showEvent(QShowEvent *event) { + timer->start(10 * 1000); } -void OffroadHome::closeAlerts() { - center_layout->setCurrentIndex(0); +void OffroadHome::hideEvent(QHideEvent *event) { + timer->stop(); } void OffroadHome::refresh() { - bool first_refresh = !date->text().size(); - if (!isVisible() && !first_refresh) { - return; - } - date->setText(QDateTime::currentDateTime().toString("dddd, MMMM d")); - // update alerts + bool updateAvailable = update_widget->refresh(); + int alerts = alerts_widget->refresh(); - alerts_widget->refresh(); - if (!alerts_widget->alertCount && !alerts_widget->updateAvailable) { - emit closeAlerts(); - alert_notification->setVisible(false); - return; + // pop-up new notification + int idx = center_layout->currentIndex(); + if (!updateAvailable && !alerts) { + idx = 0; + } else if (updateAvailable && (!update_notif->isVisible() || (!alerts && idx == 2))) { + idx = 1; + } else if (alerts && (!alert_notif->isVisible() || (!updateAvailable && idx == 1))) { + idx = 2; } + center_layout->setCurrentIndex(idx); - if (alerts_widget->updateAvailable) { - alert_notification->setText("UPDATE"); - } else { - int alerts = alerts_widget->alertCount; - alert_notification->setText(QString::number(alerts) + " ALERT" + (alerts == 1 ? "" : "S")); + update_notif->setVisible(updateAvailable); + alert_notif->setVisible(alerts); + if (alerts) { + alert_notif->setText(QString::number(alerts) + " ALERT" + (alerts > 1 ? "S" : "")); } - - if (!alert_notification->isVisible() && !first_refresh) { - emit openAlerts(); - } - alert_notification->setVisible(true); - - // Red background for alerts, blue for update available - QString style = QString(R"( - padding: 15px; - padding-left: 30px; - padding-right: 30px; - border: 1px solid; - border-radius: 5px; - font-size: 40px; - font-weight: 500; - background-color: #E22C2C; - )"); - if (alerts_widget->updateAvailable) { - style.replace("#E22C2C", "#364DEF"); - } - alert_notification->setStyleSheet(style); } diff --git a/selfdrive/ui/qt/home.h b/selfdrive/ui/qt/home.h index db3e2f8f6..e133710bc 100644 --- a/selfdrive/ui/qt/home.h +++ b/selfdrive/ui/qt/home.h @@ -19,21 +19,18 @@ class OffroadHome : public QFrame { public: explicit OffroadHome(QWidget* parent = 0); -protected: - void showEvent(QShowEvent *event) override; - private: - QTimer* timer; + void showEvent(QShowEvent *event) override; + void hideEvent(QHideEvent *event) override; + void refresh(); + QTimer* timer; QLabel* date; QStackedLayout* center_layout; + UpdateAlert *update_widget; OffroadAlert* alerts_widget; - QPushButton* alert_notification; - -public slots: - void closeAlerts(); - void openAlerts(); - void refresh(); + QPushButton* alert_notif; + QPushButton* update_notif; }; class HomeWindow : public QWidget { @@ -54,6 +51,7 @@ signals: public slots: void offroadTransition(bool offroad); void showDriverView(bool show); + void showSidebar(bool show); protected: void mousePressEvent(QMouseEvent* e) override; diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index 901315ac5..aa3e523da 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -1,67 +1,60 @@ -#include "networking.h" +#include "selfdrive/ui/qt/offroad/networking.h" #include #include #include -#include +#include #include "selfdrive/ui/qt/widgets/scrollview.h" #include "selfdrive/ui/qt/util.h" -// Networking functions -Networking::Networking(QWidget* parent, bool show_advanced) : QWidget(parent), show_advanced(show_advanced){ - s = new QStackedLayout; - - QLabel* warning = new QLabel("Network manager is inactive!"); - warning->setAlignment(Qt::AlignCenter); - warning->setStyleSheet(R"(font-size: 65px;)"); - - s->addWidget(warning); - setLayout(s); - - QTimer* timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, this, &Networking::refresh); - timer->start(5000); - attemptInitialization(); +void NetworkStrengthWidget::paintEvent(QPaintEvent* event) { + QPainter p(this); + p.setRenderHint(QPainter::Antialiasing); + p.setPen(Qt::NoPen); + const QColor gray(0x54, 0x54, 0x54); + for (int i = 0, x = 0; i < 5; ++i) { + p.setBrush(i < strength_ ? Qt::white : gray); + p.drawEllipse(x, 0, 15, 15); + x += 20; + } } -void Networking::attemptInitialization(){ - // Checks if network manager is active - try { - wifi = new WifiManager(this); - } catch (std::exception &e) { - return; - } +// Networking functions +Networking::Networking(QWidget* parent, bool show_advanced) : QWidget(parent), show_advanced(show_advanced) { + main_layout = new QStackedLayout(this); + + wifi = new WifiManager(this); connect(wifi, &WifiManager::wrongPassword, this, &Networking::wrongPassword); + connect(wifi, &WifiManager::refreshSignal, this, &Networking::refresh); - QVBoxLayout* vlayout = new QVBoxLayout; - + QWidget* wifiScreen = new QWidget(this); + QVBoxLayout* vlayout = new QVBoxLayout(wifiScreen); if (show_advanced) { QPushButton* advancedSettings = new QPushButton("Advanced"); + advancedSettings->setObjectName("advancedBtn"); advancedSettings->setStyleSheet("margin-right: 30px;"); advancedSettings->setFixedSize(350, 100); - connect(advancedSettings, &QPushButton::released, [=](){ s->setCurrentWidget(an); }); + connect(advancedSettings, &QPushButton::released, [=]() { main_layout->setCurrentWidget(an); }); vlayout->addSpacing(10); vlayout->addWidget(advancedSettings, 0, Qt::AlignRight); vlayout->addSpacing(10); } wifiWidget = new WifiUI(this, wifi); + wifiWidget->setObjectName("wifiWidget"); connect(wifiWidget, &WifiUI::connectToNetwork, this, &Networking::connectToNetwork); vlayout->addWidget(new ScrollView(wifiWidget, this), 1); - - QWidget* wifiScreen = new QWidget(this); - wifiScreen->setLayout(vlayout); - s->addWidget(wifiScreen); + main_layout->addWidget(wifiScreen); an = new AdvancedNetworking(this, wifi); - connect(an, &AdvancedNetworking::backPress, [=](){s->setCurrentWidget(wifiScreen);}); - s->addWidget(an); + connect(an, &AdvancedNetworking::backPress, [=]() { main_layout->setCurrentWidget(wifiScreen); }); + main_layout->addWidget(an); setStyleSheet(R"( - QPushButton { + #wifiWidget > QPushButton, #back_btn, #advancedBtn { font-size: 50px; margin: 0px; padding: 15px; @@ -70,167 +63,180 @@ void Networking::attemptInitialization(){ color: #dddddd; background-color: #444444; } - QPushButton:disabled { + #wifiWidget > QPushButton:disabled { color: #777777; background-color: #222222; } )"); - s->setCurrentWidget(wifiScreen); - ui_setup_complete = true; + main_layout->setCurrentWidget(wifiScreen); } -void Networking::refresh(){ - if (!this->isVisible()) { - return; - } - if (!ui_setup_complete) { - attemptInitialization(); - if (!ui_setup_complete) { - return; - } - } +void Networking::refresh() { wifiWidget->refresh(); an->refresh(); } -void Networking::connectToNetwork(Network n) { - if (n.security_type == SecurityType::OPEN) { +void Networking::connectToNetwork(const Network &n) { + if (wifi->isKnownConnection(n.ssid)) { + wifi->activateWifiConnection(n.ssid); + } else if (n.security_type == SecurityType::OPEN) { wifi->connect(n); } else if (n.security_type == SecurityType::WPA) { - QString pass = InputDialog::getText("Enter password for \"" + n.ssid + "\"", 8); - wifi->connect(n, pass); + QString pass = InputDialog::getText("Enter password for \"" + n.ssid + "\"", this, 8); + if (!pass.isEmpty()) { + wifi->connect(n, pass); + } } } -void Networking::wrongPassword(QString ssid) { +void Networking::wrongPassword(const QString &ssid) { for (Network n : wifi->seen_networks) { if (n.ssid == ssid) { - QString pass = InputDialog::getText("Wrong password for \"" + n.ssid +"\"", 8); - wifi->connect(n, pass); + QString pass = InputDialog::getText("Wrong password for \"" + n.ssid +"\"", this, 8); + if (!pass.isEmpty()) { + wifi->connect(n, pass); + } return; } } } +void Networking::showEvent(QShowEvent* event) { + // Wait to refresh to avoid delay when showing Networking widget + QTimer::singleShot(300, this, [=]() { + if (this->isVisible()) { + wifi->refreshNetworks(); + refresh(); + } + }); +} + // AdvancedNetworking functions -AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWidget(parent), wifi(wifi){ +AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWidget(parent), wifi(wifi) { - QVBoxLayout* vlayout = new QVBoxLayout; - vlayout->setMargin(40); - vlayout->setSpacing(20); + QVBoxLayout* main_layout = new QVBoxLayout(this); + main_layout->setMargin(40); + main_layout->setSpacing(20); // Back button QPushButton* back = new QPushButton("Back"); + back->setObjectName("back_btn"); back->setFixedSize(500, 100); - connect(back, &QPushButton::released, [=](){emit backPress();}); - vlayout->addWidget(back, 0, Qt::AlignLeft); + connect(back, &QPushButton::released, [=]() { emit backPress(); }); + main_layout->addWidget(back, 0, Qt::AlignLeft); // Enable tethering layout - ToggleControl *tetheringToggle = new ToggleControl("Enable Tethering", "", "", wifi->tetheringEnabled()); - vlayout->addWidget(tetheringToggle); + ToggleControl *tetheringToggle = new ToggleControl("Enable Tethering", "", "", wifi->isTetheringEnabled()); + main_layout->addWidget(tetheringToggle); QObject::connect(tetheringToggle, &ToggleControl::toggleFlipped, this, &AdvancedNetworking::toggleTethering); - vlayout->addWidget(horizontal_line(), 0); + main_layout->addWidget(horizontal_line(), 0); // Change tethering password - editPasswordButton = new ButtonControl("Tethering Password", "EDIT", "", [=](){ - QString pass = InputDialog::getText("Enter new tethering password", 8); - if (pass.size()) { + ButtonControl *editPasswordButton = new ButtonControl("Tethering Password", "EDIT"); + connect(editPasswordButton, &ButtonControl::released, [=]() { + QString pass = InputDialog::getText("Enter new tethering password", this, 8, wifi->getTetheringPassword()); + if (!pass.isEmpty()) { wifi->changeTetheringPassword(pass); } }); - vlayout->addWidget(editPasswordButton, 0); - vlayout->addWidget(horizontal_line(), 0); + main_layout->addWidget(editPasswordButton, 0); + main_layout->addWidget(horizontal_line(), 0); // IP address ipLabel = new LabelControl("IP Address", wifi->ipv4_address); - vlayout->addWidget(ipLabel, 0); - vlayout->addWidget(horizontal_line(), 0); + main_layout->addWidget(ipLabel, 0); + main_layout->addWidget(horizontal_line(), 0); // SSH keys - vlayout->addWidget(new SshToggle()); - vlayout->addWidget(horizontal_line(), 0); - vlayout->addWidget(new SshControl()); + main_layout->addWidget(new SshToggle()); + main_layout->addWidget(horizontal_line(), 0); + main_layout->addWidget(new SshControl()); - vlayout->addStretch(1); - setLayout(vlayout); + main_layout->addStretch(1); } -void AdvancedNetworking::refresh(){ +void AdvancedNetworking::refresh() { ipLabel->setText(wifi->ipv4_address); update(); } -void AdvancedNetworking::toggleTethering(bool enable) { - if (enable) { - wifi->enableTethering(); - } else { - wifi->disableTethering(); - } - editPasswordButton->setEnabled(!enable); +void AdvancedNetworking::toggleTethering(bool enabled) { + wifi->setTetheringEnabled(enabled); } - // WifiUI functions WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) { - vlayout = new QVBoxLayout; + main_layout = new QVBoxLayout(this); // Scan on startup QLabel *scanning = new QLabel("Scanning for networks"); scanning->setStyleSheet(R"(font-size: 65px;)"); - vlayout->addWidget(scanning, 0, Qt::AlignCenter); - vlayout->setSpacing(25); - - setLayout(vlayout); + main_layout->addWidget(scanning, 0, Qt::AlignCenter); + main_layout->setSpacing(25); } void WifiUI::refresh() { - wifi->request_scan(); - wifi->refreshNetworks(); - clearLayout(vlayout); - - connectButtons = new QButtonGroup(this); // TODO check if this is a leak - QObject::connect(connectButtons, qOverload(&QButtonGroup::buttonClicked), this, &WifiUI::handleButton); + clearLayout(main_layout); + if (wifi->seen_networks.size() == 0) { + QLabel *scanning = new QLabel("No networks found. Scanning..."); + scanning->setStyleSheet(R"(font-size: 65px;)"); + main_layout->addWidget(scanning, 0, Qt::AlignCenter); + return; + } int i = 0; for (Network &network : wifi->seen_networks) { QHBoxLayout *hlayout = new QHBoxLayout; - hlayout->addSpacing(50); - QLabel *ssid_label = new QLabel(QString::fromUtf8(network.ssid)); + ElidedLabel *ssid_label = new ElidedLabel(network.ssid); ssid_label->setStyleSheet("font-size: 55px;"); hlayout->addWidget(ssid_label, 1, Qt::AlignLeft); - // TODO: don't use images for this + if (wifi->isKnownConnection(network.ssid) && !wifi->isTetheringEnabled()) { + QPushButton *forgetBtn = new QPushButton(); + QPixmap pix("../assets/offroad/icon_close.svg"); + + forgetBtn->setIcon(QIcon(pix)); + forgetBtn->setIconSize(QSize(35, 35)); + forgetBtn->setStyleSheet("QPushButton { background-color: #E22C2C; }"); + forgetBtn->setFixedSize(100, 90); + + QObject::connect(forgetBtn, &QPushButton::released, [=]() { + if (ConfirmationDialog::confirm("Are you sure you want to forget " + QString::fromUtf8(network.ssid) + "?", this)) { + wifi->forgetConnection(network.ssid); + } + }); + + hlayout->addWidget(forgetBtn, 0, Qt::AlignRight); + } else if (network.security_type == SecurityType::WPA) { + QLabel *lockIcon = new QLabel(); + QPixmap pix("../assets/offroad/icon_lock_closed.svg"); + lockIcon->setPixmap(pix.scaledToWidth(35, Qt::SmoothTransformation)); + lockIcon->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + lockIcon->setStyleSheet("QLabel { margin: 0px; padding-left: 15px; padding-right: 15px; }"); + + hlayout->addWidget(lockIcon, 0, Qt::AlignRight); + } + // strength indicator unsigned int strength_scale = network.strength / 17; - QPixmap pix("../assets/images/network_" + QString::number(strength_scale) + ".png"); - QLabel *icon = new QLabel(); - icon->setPixmap(pix.scaledToWidth(100, Qt::SmoothTransformation)); - icon->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); - hlayout->addWidget(icon, 0, Qt::AlignRight); + hlayout->addWidget(new NetworkStrengthWidget(strength_scale), 0, Qt::AlignRight); // connect button QPushButton* btn = new QPushButton(network.security_type == SecurityType::UNSUPPORTED ? "Unsupported" : (network.connected == ConnectedType::CONNECTED ? "Connected" : (network.connected == ConnectedType::CONNECTING ? "Connecting" : "Connect"))); btn->setDisabled(network.connected == ConnectedType::CONNECTED || network.connected == ConnectedType::CONNECTING || network.security_type == SecurityType::UNSUPPORTED); btn->setFixedWidth(350); + QObject::connect(btn, &QPushButton::clicked, this, [=]() { emit connectToNetwork(network); }); + hlayout->addWidget(btn, 0, Qt::AlignRight); - - connectButtons->addButton(btn, i); - - vlayout->addLayout(hlayout, 1); + main_layout->addLayout(hlayout, 1); // Don't add the last horizontal line if (i+1 < wifi->seen_networks.size()) { - vlayout->addWidget(horizontal_line(), 0); + main_layout->addWidget(horizontal_line(), 0); } i++; } - vlayout->addStretch(3); -} - -void WifiUI::handleButton(QAbstractButton* button) { - QPushButton* btn = static_cast(button); - Network n = wifi->seen_networks[connectButtons->id(btn)]; - emit connectToNetwork(n); + main_layout->addStretch(3); } diff --git a/selfdrive/ui/qt/offroad/networking.h b/selfdrive/ui/qt/offroad/networking.h index 9fa1cfe88..7c0ad319b 100644 --- a/selfdrive/ui/qt/offroad/networking.h +++ b/selfdrive/ui/qt/offroad/networking.h @@ -1,8 +1,6 @@ #pragma once #include -#include -#include #include #include @@ -11,6 +9,17 @@ #include "selfdrive/ui/qt/widgets/ssh_keys.h" #include "selfdrive/ui/qt/widgets/toggle.h" +class NetworkStrengthWidget : public QWidget { + Q_OBJECT + +public: + explicit NetworkStrengthWidget(int strength, QWidget* parent = nullptr) : strength_(strength), QWidget(parent) { setFixedSize(100, 15); } + +private: + void paintEvent(QPaintEvent* event) override; + int strength_ = 0; +}; + class WifiUI : public QWidget { Q_OBJECT @@ -19,17 +28,13 @@ public: private: WifiManager *wifi = nullptr; - QVBoxLayout *vlayout; - - QButtonGroup *connectButtons; - bool tetheringEnabled; + QVBoxLayout* main_layout; signals: - void connectToNetwork(Network n); + void connectToNetwork(const Network &n); public slots: void refresh(); - void handleButton(QAbstractButton* m_button); }; class AdvancedNetworking : public QWidget { @@ -39,14 +44,13 @@ public: private: LabelControl* ipLabel; - ButtonControl* editPasswordButton; WifiManager* wifi = nullptr; signals: void backPress(); public slots: - void toggleTethering(bool enable); + void toggleTethering(bool enabled); void refresh(); }; @@ -57,21 +61,21 @@ public: explicit Networking(QWidget* parent = 0, bool show_advanced = true); private: - QStackedLayout* s = nullptr; // nm_warning, wifiScreen, advanced + QStackedLayout* main_layout = nullptr; // nm_warning, wifiScreen, advanced QWidget* wifiScreen = nullptr; AdvancedNetworking* an = nullptr; - bool ui_setup_complete = false; bool show_advanced; - Network selectedNetwork; - WifiUI* wifiWidget; WifiManager* wifi = nullptr; - void attemptInitialization(); + +protected: + void showEvent(QShowEvent* event) override; + +public slots: + void refresh(); private slots: - void connectToNetwork(Network n); - void refresh(); - void wrongPassword(QString ssid); + void connectToNetwork(const Network &n); + void wrongPassword(const QString &ssid); }; - diff --git a/selfdrive/ui/qt/offroad/networkmanager.h b/selfdrive/ui/qt/offroad/networkmanager.h new file mode 100644 index 000000000..d90371b60 --- /dev/null +++ b/selfdrive/ui/qt/offroad/networkmanager.h @@ -0,0 +1,37 @@ +/** + * We are using a NetworkManager DBUS API : https://developer.gnome.org/NetworkManager/1.26/spec.html + * */ + +// https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApFlags +const int NM_802_11_AP_FLAGS_NONE = 0x00000000; +const int NM_802_11_AP_FLAGS_PRIVACY = 0x00000001; +const int NM_802_11_AP_FLAGS_WPS = 0x00000002; + +// https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApSecurityFlags +const int NM_802_11_AP_SEC_PAIR_WEP40 = 0x00000001; +const int NM_802_11_AP_SEC_PAIR_WEP104 = 0x00000002; +const int NM_802_11_AP_SEC_GROUP_WEP40 = 0x00000010; +const int NM_802_11_AP_SEC_GROUP_WEP104 = 0x00000020; +const int NM_802_11_AP_SEC_KEY_MGMT_PSK = 0x00000100; +const int NM_802_11_AP_SEC_KEY_MGMT_802_1X = 0x00000200; + +const QString NM_DBUS_PATH = "/org/freedesktop/NetworkManager"; +const QString NM_DBUS_PATH_SETTINGS = "/org/freedesktop/NetworkManager/Settings"; + +const QString NM_DBUS_INTERFACE = "org.freedesktop.NetworkManager"; +const QString NM_DBUS_INTERFACE_PROPERTIES = "org.freedesktop.DBus.Properties"; +const QString NM_DBUS_INTERFACE_SETTINGS = "org.freedesktop.NetworkManager.Settings"; +const QString NM_DBUS_INTERFACE_SETTINGS_CONNECTION = "org.freedesktop.NetworkManager.Settings.Connection"; +const QString NM_DBUS_INTERFACE_DEVICE = "org.freedesktop.NetworkManager.Device"; +const QString NM_DBUS_INTERFACE_DEVICE_WIRELESS = "org.freedesktop.NetworkManager.Device.Wireless"; +const QString NM_DBUS_INTERFACE_ACCESS_POINT = "org.freedesktop.NetworkManager.AccessPoint"; +const QString NM_DBUS_INTERFACE_ACTIVE_CONNECTION = "org.freedesktop.NetworkManager.Connection.Active"; +const QString NM_DBUS_INTERFACE_IP4_CONFIG = "org.freedesktop.NetworkManager.IP4Config"; + +const QString NM_DBUS_SERVICE = "org.freedesktop.NetworkManager"; + +const int NM_DEVICE_STATE_ACTIVATED = 100; +const int NM_DEVICE_STATE_NEED_AUTH = 60; +const int NM_DEVICE_TYPE_WIFI = 2; +const int NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT = 8; +const int DBUS_TIMEOUT = 100; diff --git a/selfdrive/ui/qt/offroad/onboarding.cc b/selfdrive/ui/qt/offroad/onboarding.cc index c0ede84a6..0034f3a39 100644 --- a/selfdrive/ui/qt/offroad/onboarding.cc +++ b/selfdrive/ui/qt/offroad/onboarding.cc @@ -1,42 +1,33 @@ -#include "onboarding.h" +#include "selfdrive/ui/qt/offroad/onboarding.h" -#include #include #include #include #include #include -#include "selfdrive/common/params.h" #include "selfdrive/common/util.h" -#include "selfdrive/ui/qt/home.h" +#include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/input.h" - void TrainingGuide::mouseReleaseEvent(QMouseEvent *e) { - QPoint touch = QPoint(e->x(), e->y()) - imageCorner; - //qDebug() << touch.x() << ", " << touch.y(); - - // Check for restart - if (currentIndex == (boundingBox.size() - 1) && 200 <= touch.x() && touch.x() <= 920 && - 760 <= touch.y() && touch.y() <= 960) { - currentIndex = 0; - } else if (boundingBox[currentIndex][0] <= touch.x() && touch.x() <= boundingBox[currentIndex][1] && - boundingBox[currentIndex][2] <= touch.y() && touch.y() <= boundingBox[currentIndex][3]) { + if (boundingRect[currentIndex].contains(e->x(), e->y())) { currentIndex += 1; + } else if (currentIndex == (boundingRect.size() - 2) && boundingRect.last().contains(e->x(), e->y())) { + currentIndex = 0; } - if (currentIndex >= boundingBox.size()) { + if (currentIndex >= (boundingRect.size() - 1)) { emit completedTraining(); } else { - image.load("../assets/training/step" + QString::number(currentIndex) + ".png"); + image.load(IMG_PATH + "step" + QString::number(currentIndex) + ".png"); update(); } } void TrainingGuide::showEvent(QShowEvent *event) { currentIndex = 0; - image.load("../assets/training/step0.png"); + image.load(IMG_PATH + "step0.png"); } void TrainingGuide::paintEvent(QPaintEvent *event) { @@ -49,7 +40,6 @@ void TrainingGuide::paintEvent(QPaintEvent *event) { QRect rect(image.rect()); rect.moveCenter(bg.center()); painter.drawImage(rect.topLeft(), image); - imageCorner = rect.topLeft(); } void TermsPage::showEvent(QShowEvent *event) { @@ -58,56 +48,59 @@ void TermsPage::showEvent(QShowEvent *event) { return; } - QVBoxLayout *main_layout = new QVBoxLayout; - main_layout->setMargin(40); - main_layout->setSpacing(40); + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setContentsMargins(45, 35, 45, 45); + main_layout->setSpacing(0); + + QLabel *title = new QLabel("Terms & Conditions"); + title->setStyleSheet("font-size: 90px; font-weight: 600;"); + main_layout->addWidget(title); + + main_layout->addSpacing(30); QQuickWidget *text = new QQuickWidget(this); text->setResizeMode(QQuickWidget::SizeRootObjectToView); text->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); text->setAttribute(Qt::WA_AlwaysStackOnTop); - text->setClearColor(Qt::transparent); + text->setClearColor(QColor("#1B1B1B")); QString text_view = util::read_file("../assets/offroad/tc.html").c_str(); text->rootContext()->setContextProperty("text_view", text_view); - text->rootContext()->setContextProperty("font_size", 55); text->setSource(QUrl::fromLocalFile("qt/offroad/text_view.qml")); - main_layout->addWidget(text); + main_layout->addWidget(text, 1); + main_layout->addSpacing(50); QObject *obj = (QObject*)text->rootObject(); - QObject::connect(obj, SIGNAL(qmlSignal()), SLOT(enableAccept())); + QObject::connect(obj, SIGNAL(scroll()), SLOT(enableAccept())); QHBoxLayout* buttons = new QHBoxLayout; + buttons->setMargin(0); + buttons->setSpacing(45); main_layout->addLayout(buttons); - decline_btn = new QPushButton("Decline"); + QPushButton *decline_btn = new QPushButton("Decline"); buttons->addWidget(decline_btn); QObject::connect(decline_btn, &QPushButton::released, this, &TermsPage::declinedTerms); - buttons->addSpacing(50); - accept_btn = new QPushButton("Scroll to accept"); accept_btn->setEnabled(false); - buttons->addWidget(accept_btn); - QObject::connect(accept_btn, &QPushButton::released, this, &TermsPage::acceptedTerms); - - setLayout(main_layout); - setStyleSheet(R"( + accept_btn->setStyleSheet(R"( QPushButton { - padding: 50px; - font-size: 50px; - border-radius: 10px; - background-color: #292929; + background-color: #465BEA; + } + QPushButton:disabled { + background-color: #4F4F4F; } )"); + buttons->addWidget(accept_btn); + QObject::connect(accept_btn, &QPushButton::released, this, &TermsPage::acceptedTerms); } -void TermsPage::enableAccept(){ - accept_btn->setText("Accept"); +void TermsPage::enableAccept() { + accept_btn->setText("Agree"); accept_btn->setEnabled(true); - return; } void DeclinePage::showEvent(QShowEvent *event) { @@ -115,51 +108,39 @@ void DeclinePage::showEvent(QShowEvent *event) { return; } - QVBoxLayout *main_layout = new QVBoxLayout; - main_layout->setMargin(40); + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setMargin(45); main_layout->setSpacing(40); QLabel *text = new QLabel(this); - text->setText("You must accept the Terms and Conditions in order to use openpilot!"); - text->setStyleSheet(R"(font-size: 50px;)"); + text->setText("You must accept the Terms and Conditions in order to use openpilot."); + text->setStyleSheet(R"(font-size: 80px; font-weight: 300; margin: 200px;)"); + text->setWordWrap(true); main_layout->addWidget(text, 0, Qt::AlignCenter); QHBoxLayout* buttons = new QHBoxLayout; + buttons->setSpacing(45); main_layout->addLayout(buttons); - back_btn = new QPushButton("Back"); + QPushButton *back_btn = new QPushButton("Back"); buttons->addWidget(back_btn); - buttons->addSpacing(50); QObject::connect(back_btn, &QPushButton::released, this, &DeclinePage::getBack); - uninstall_btn = new QPushButton("Decline, uninstall openpilot"); - uninstall_btn->setStyleSheet("background-color: #E22C2C;"); + QPushButton *uninstall_btn = new QPushButton("Decline, uninstall " + getBrand()); + uninstall_btn->setStyleSheet("background-color: #B73D3D"); buttons->addWidget(uninstall_btn); - - QObject::connect(uninstall_btn, &QPushButton::released, [=](){ - if (ConfirmationDialog::confirm("Are you sure you want to uninstall?", this)) { - Params().putBool("DoUninstall", true); - } + QObject::connect(uninstall_btn, &QPushButton::released, [=]() { + Params().putBool("DoUninstall", true); }); - - setLayout(main_layout); - setStyleSheet(R"( - QPushButton { - padding: 50px; - font-size: 50px; - border-radius: 10px; - background-color: #292929; - } - )"); } void OnboardingWindow::updateActiveScreen() { - updateOnboardingStatus(); - + bool accepted_terms = params.get("HasAcceptedTerms") == current_terms_version; + bool training_done = params.get("CompletedTrainingVersion") == current_training_version; if (!accepted_terms) { setCurrentIndex(0); - } else if (!training_done) { + } else if (!training_done && !params.getBool("Passive")) { setCurrentIndex(1); } else { emit onboardingDone(); @@ -167,35 +148,27 @@ void OnboardingWindow::updateActiveScreen() { } OnboardingWindow::OnboardingWindow(QWidget *parent) : QStackedWidget(parent) { - params = Params(); - current_terms_version = params.get("TermsVersion", false); - current_training_version = params.get("TrainingVersion", false); + current_terms_version = params.get("TermsVersion"); + current_training_version = params.get("TrainingVersion"); TermsPage* terms = new TermsPage(this); addWidget(terms); - - connect(terms, &TermsPage::acceptedTerms, [=](){ + connect(terms, &TermsPage::acceptedTerms, [=]() { Params().put("HasAcceptedTerms", current_terms_version); updateActiveScreen(); }); + connect(terms, &TermsPage::declinedTerms, [=]() { setCurrentIndex(2); }); TrainingGuide* tr = new TrainingGuide(this); - connect(tr, &TrainingGuide::completedTraining, [=](){ + addWidget(tr); + connect(tr, &TrainingGuide::completedTraining, [=]() { Params().put("CompletedTrainingVersion", current_training_version); updateActiveScreen(); }); - addWidget(tr); DeclinePage* declinePage = new DeclinePage(this); addWidget(declinePage); - - connect(terms, &TermsPage::declinedTerms, [=](){ - setCurrentIndex(2); - }); - - connect(declinePage, &DeclinePage::getBack, [=](){ - updateActiveScreen(); - }); + connect(declinePage, &DeclinePage::getBack, [=]() { updateActiveScreen(); }); setStyleSheet(R"( * { @@ -203,25 +176,15 @@ OnboardingWindow::OnboardingWindow(QWidget *parent) : QStackedWidget(parent) { background-color: black; } QPushButton { - padding: 50px; - border-radius: 30px; - background-color: #292929; - } - QPushButton:disabled { - color: #777777; - background-color: #222222; + height: 160px; + font-size: 55px; + font-weight: 400; + border-radius: 10px; + background-color: #4F4F4F; } )"); +} +void OnboardingWindow::showEvent(QShowEvent *event) { updateActiveScreen(); } - -void OnboardingWindow::updateOnboardingStatus() { - accepted_terms = params.get("HasAcceptedTerms", false).compare(current_terms_version) == 0; - training_done = params.get("CompletedTrainingVersion", false).compare(current_training_version) == 0; -} - -bool OnboardingWindow::isOnboardingDone() { - updateOnboardingStatus(); - return accepted_terms && training_done; -} diff --git a/selfdrive/ui/qt/offroad/onboarding.h b/selfdrive/ui/qt/offroad/onboarding.h index 51a055d87..bcd40e157 100644 --- a/selfdrive/ui/qt/offroad/onboarding.h +++ b/selfdrive/ui/qt/offroad/onboarding.h @@ -4,10 +4,10 @@ #include #include #include -#include #include #include "selfdrive/common/params.h" +#include "selfdrive/ui/qt/qt_window.h" class TrainingGuide : public QFrame { Q_OBJECT @@ -15,39 +15,64 @@ class TrainingGuide : public QFrame { public: explicit TrainingGuide(QWidget *parent = 0) : QFrame(parent) {}; -protected: +private: void showEvent(QShowEvent *event) override; void paintEvent(QPaintEvent *event) override; void mouseReleaseEvent(QMouseEvent* e) override; -private: QImage image; - QPoint imageCorner; int currentIndex = 0; - // Bounding boxes for the a given training guide step - // (minx, maxx, miny, maxy) - QVector> boundingBox { - {650, 1375, 700, 900}, - {1600, 1920, 0, 1080}, - {1600, 1920, 0, 1080}, - {1240, 1750, 480, 1080}, - {1570, 1780, 620, 750}, - {1600, 1920, 0, 1080}, - {1630, 1740, 620, 780}, - {1200, 1920, 0, 1080}, - {1455, 1850, 400, 660}, - {1460, 1800, 195, 520}, - {1600, 1920, 0, 1080}, - {1350, 1920, 65, 1080}, - {1600, 1920, 0, 1080}, - {1570, 1900, 130, 1000}, - {1350, 1770, 500, 700}, - {1600, 1920, 0, 1080}, - {1600, 1920, 0, 1080}, - {1000, 1800, 760, 954}, + // Bounding boxes for each training guide step + const QRect continueBtnStandard = {1610, 0, 310, 1080}; + QVector boundingRectStandard { + QRect(650, 710, 720, 190), + continueBtnStandard, + continueBtnStandard, + QRect(1470, 515, 235, 565), + QRect(1580, 630, 215, 130), + continueBtnStandard, + QRect(1580, 630, 215, 130), + QRect(1210, 0, 485, 590), + QRect(1460, 400, 375, 210), + QRect(1460, 210, 300, 310), + continueBtnStandard, + QRect(1375, 80, 545, 1000), + continueBtnStandard, + QRect(1610, 130, 280, 800), + QRect(1385, 485, 400, 270), + continueBtnStandard, + continueBtnStandard, + QRect(1036, 769, 718, 189), + QRect(201, 769, 718, 189), }; + const QRect continueBtnWide = {1850, 0, 310, 1080}; + QVector boundingRectWide { + QRect(654, 721, 718, 189), + continueBtnWide, + continueBtnWide, + QRect(1589, 530, 345, 555), + QRect(1660, 630, 195, 125), + continueBtnWide, + QRect(1820, 630, 180, 155), + QRect(1360, 0, 460, 620), + QRect(1570, 400, 375, 215), + QRect(1610, 210, 295, 310), + continueBtnWide, + QRect(1555, 90, 610, 990), + continueBtnWide, + QRect(1600, 140, 280, 790), + QRect(1385, 490, 750, 270), + continueBtnWide, + continueBtnWide, + QRect(1138, 755, 718, 189), + QRect(303, 755, 718, 189), + }; + + const QString IMG_PATH = vwp_w == 2160 ? "../assets/training_wide/" : "../assets/training/"; + const QVector boundingRect = vwp_w == 2160 ? boundingRectWide : boundingRectStandard; + signals: void completedTraining(); }; @@ -59,16 +84,14 @@ class TermsPage : public QFrame { public: explicit TermsPage(QWidget *parent = 0) : QFrame(parent) {}; -protected: - void showEvent(QShowEvent *event) override; - -private: - QPushButton *accept_btn; - QPushButton *decline_btn; - public slots: void enableAccept(); +private: + void showEvent(QShowEvent *event) override; + + QPushButton *accept_btn; + signals: void acceptedTerms(); void declinedTerms(); @@ -80,12 +103,8 @@ class DeclinePage : public QFrame { public: explicit DeclinePage(QWidget *parent = 0) : QFrame(parent) {}; -protected: - void showEvent(QShowEvent *event) override; - private: - QPushButton *back_btn; - QPushButton *uninstall_btn; + void showEvent(QShowEvent *event) override; signals: void getBack(); @@ -96,20 +115,15 @@ class OnboardingWindow : public QStackedWidget { public: explicit OnboardingWindow(QWidget *parent = 0); - bool isOnboardingDone(); private: + void showEvent(QShowEvent *event) override; + void updateActiveScreen(); + Params params; std::string current_terms_version; std::string current_training_version; - bool accepted_terms = false; - bool training_done = false; - void updateOnboardingStatus(); signals: void onboardingDone(); - void resetTrainingGuide(); - -public slots: - void updateActiveScreen(); }; diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 39108667a..6c61166dd 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -1,17 +1,23 @@ -#include "settings.h" +#include "selfdrive/ui/qt/offroad/settings.h" #include #include +#include + #ifndef QCOM #include "selfdrive/ui/qt/offroad/networking.h" #endif + +#ifdef ENABLE_MAPS +#include "selfdrive/ui/qt/maps/map_settings.h" +#endif + #include "selfdrive/common/params.h" #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" #include "selfdrive/ui/qt/widgets/controls.h" #include "selfdrive/ui/qt/widgets/input.h" -#include "selfdrive/ui/qt/widgets/offroad_alerts.h" #include "selfdrive/ui/qt/widgets/scrollview.h" #include "selfdrive/ui/qt/widgets/ssh_keys.h" #include "selfdrive/ui/qt/widgets/toggle.h" @@ -19,7 +25,7 @@ #include "selfdrive/ui/qt/util.h" TogglesPanel::TogglesPanel(QWidget *parent) : QWidget(parent) { - QVBoxLayout *toggles_list = new QVBoxLayout(); + QVBoxLayout *main_layout = new QVBoxLayout(this); QList toggles; @@ -76,51 +82,51 @@ TogglesPanel::TogglesPanel(QWidget *parent) : QWidget(parent) { QObject::connect(toggles.back(), &ToggleControl::toggleFlipped, [=](bool state) { Params().remove("CalibrationParams"); }); - - toggles.append(new ParamControl("EnableLteOnroad", - "Enable LTE while onroad", - "", - "../assets/offroad/icon_network.png", - this)); } +#ifdef ENABLE_MAPS + toggles.append(new ParamControl("NavSettingTime24h", + "Show ETA in 24h format", + "Use 24h format instead of am/pm", + "../assets/offroad/icon_metric.png", + this)); +#endif + bool record_lock = Params().getBool("RecordFrontLock"); record_toggle->setEnabled(!record_lock); - for(ParamControl *toggle : toggles){ - if(toggles_list->count() != 0){ - toggles_list->addWidget(horizontal_line()); + for(ParamControl *toggle : toggles) { + if(main_layout->count() != 0) { + main_layout->addWidget(horizontal_line()); } - toggles_list->addWidget(toggle); + main_layout->addWidget(toggle); } - - setLayout(toggles_list); } DevicePanel::DevicePanel(QWidget* parent) : QWidget(parent) { - QVBoxLayout *device_layout = new QVBoxLayout; + QVBoxLayout *main_layout = new QVBoxLayout(this); Params params = Params(); QString dongle = QString::fromStdString(params.get("DongleId", false)); - device_layout->addWidget(new LabelControl("Dongle ID", dongle)); - device_layout->addWidget(horizontal_line()); + main_layout->addWidget(new LabelControl("Dongle ID", dongle)); + main_layout->addWidget(horizontal_line()); QString serial = QString::fromStdString(params.get("HardwareSerial", false)); - device_layout->addWidget(new LabelControl("Serial", serial)); + main_layout->addWidget(new LabelControl("Serial", serial)); // offroad-only buttons - QList offroad_btns; - offroad_btns.append(new ButtonControl("Driver Camera", "PREVIEW", - "Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)", - [=]() { emit showDriverView(); }, "", this)); + auto dcamBtn = new ButtonControl("Driver Camera", "PREVIEW", + "Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)"); + connect(dcamBtn, &ButtonControl::released, [=]() { emit showDriverView(); }); QString resetCalibDesc = "openpilot requires the device to be mounted within 4° left or right and within 5° up or down. openpilot is continuously calibrating, resetting is rarely required."; - ButtonControl *resetCalibBtn = new ButtonControl("Reset Calibration", "RESET", resetCalibDesc, [=]() { + auto resetCalibBtn = new ButtonControl("Reset Calibration", "RESET", resetCalibDesc); + connect(resetCalibBtn, &ButtonControl::released, [=]() { if (ConfirmationDialog::confirm("Are you sure you want to reset calibration?", this)) { Params().remove("CalibrationParams"); } - }, "", this); + }); connect(resetCalibBtn, &ButtonControl::showDescription, [=]() { QString desc = resetCalibDesc; std::string calib_bytes = Params().get("CalibrationParams"); @@ -142,27 +148,31 @@ DevicePanel::DevicePanel(QWidget* parent) : QWidget(parent) { } resetCalibBtn->setDescription(desc); }); - offroad_btns.append(resetCalibBtn); - offroad_btns.append(new ButtonControl("Review Training Guide", "REVIEW", - "Review the rules, features, and limitations of openpilot", [=]() { - if (ConfirmationDialog::confirm("Are you sure you want to review the training guide?", this)) { - Params().remove("CompletedTrainingVersion"); - emit reviewTrainingGuide(); - } - }, "", this)); + ButtonControl *retrainingBtn = nullptr; + if (!params.getBool("Passive")) { + retrainingBtn = new ButtonControl("Review Training Guide", "REVIEW", "Review the rules, features, and limitations of openpilot"); + connect(retrainingBtn, &ButtonControl::released, [=]() { + if (ConfirmationDialog::confirm("Are you sure you want to review the training guide?", this)) { + Params().remove("CompletedTrainingVersion"); + emit reviewTrainingGuide(); + } + }); + } - QString brand = params.getBool("Passive") ? "dashcam" : "openpilot"; - offroad_btns.append(new ButtonControl("Uninstall " + brand, "UNINSTALL", "", [=]() { + auto uninstallBtn = new ButtonControl("Uninstall " + getBrand(), "UNINSTALL"); + connect(uninstallBtn, &ButtonControl::released, [=]() { if (ConfirmationDialog::confirm("Are you sure you want to uninstall?", this)) { Params().putBool("DoUninstall", true); } - }, "", this)); + }); - for(auto &btn : offroad_btns){ - device_layout->addWidget(horizontal_line()); - QObject::connect(parent, SIGNAL(offroadTransition(bool)), btn, SLOT(setEnabled(bool))); - device_layout->addWidget(btn); + for (auto btn : {dcamBtn, resetCalibBtn, retrainingBtn, uninstallBtn}) { + if (btn) { + main_layout->addWidget(horizontal_line()); + connect(parent, SIGNAL(offroadTransition(bool)), btn, SLOT(setEnabled(bool))); + main_layout->addWidget(btn); + } } // power buttons @@ -170,6 +180,7 @@ DevicePanel::DevicePanel(QWidget* parent) : QWidget(parent) { power_layout->setSpacing(30); QPushButton *reboot_btn = new QPushButton("Reboot"); + reboot_btn->setStyleSheet("height: 120px;border-radius: 15px; background-color: #393939;"); power_layout->addWidget(reboot_btn); QObject::connect(reboot_btn, &QPushButton::released, [=]() { if (ConfirmationDialog::confirm("Are you sure you want to reboot?", this)) { @@ -178,7 +189,7 @@ DevicePanel::DevicePanel(QWidget* parent) : QWidget(parent) { }); QPushButton *poweroff_btn = new QPushButton("Power Off"); - poweroff_btn->setStyleSheet("background-color: #E22C2C;"); + poweroff_btn->setStyleSheet("height: 120px;border-radius: 15px; background-color: #E22C2C;"); power_layout->addWidget(poweroff_btn); QObject::connect(poweroff_btn, &QPushButton::released, [=]() { if (ConfirmationDialog::confirm("Are you sure you want to power off?", this)) { @@ -186,31 +197,45 @@ DevicePanel::DevicePanel(QWidget* parent) : QWidget(parent) { } }); - device_layout->addLayout(power_layout); - - setLayout(device_layout); - setStyleSheet(R"( - QPushButton { - padding: 0; - height: 120px; - border-radius: 15px; - background-color: #393939; - } - )"); + main_layout->addLayout(power_layout); } -SoftwarePanel::SoftwarePanel(QWidget* parent) : QFrame(parent) { +SoftwarePanel::SoftwarePanel(QWidget* parent) : QWidget(parent) { + gitBranchLbl = new LabelControl("Git Branch"); + gitCommitLbl = new LabelControl("Git Commit"); + osVersionLbl = new LabelControl("OS Version"); + versionLbl = new LabelControl("Version", "", QString::fromStdString(params.get("ReleaseNotes")).trimmed()); + lastUpdateLbl = new LabelControl("Last Update Check", "", "The last time openpilot successfully checked for an update. The updater only runs while the car is off."); + updateBtn = new ButtonControl("Check for Update", ""); + connect(updateBtn, &ButtonControl::released, [=]() { + if (params.getBool("IsOffroad")) { + const QString paramsPath = QString::fromStdString(params.getParamsPath()); + fs_watch->addPath(paramsPath + "/d/LastUpdateTime"); + fs_watch->addPath(paramsPath + "/d/UpdateFailedCount"); + updateBtn->setText("CHECKING"); + updateBtn->setEnabled(false); + } + std::system("pkill -1 -f selfdrive.updated"); + }); + QVBoxLayout *main_layout = new QVBoxLayout(this); - setLayout(main_layout); + QWidget *widgets[] = {versionLbl, lastUpdateLbl, updateBtn, gitBranchLbl, gitCommitLbl, osVersionLbl}; + for (int i = 0; i < std::size(widgets); ++i) { + main_layout->addWidget(widgets[i]); + if (i < std::size(widgets) - 1) { + main_layout->addWidget(horizontal_line()); + } + } + setStyleSheet(R"(QLabel {font-size: 50px;})"); fs_watch = new QFileSystemWatcher(this); QObject::connect(fs_watch, &QFileSystemWatcher::fileChanged, [=](const QString path) { - int update_failed_count = Params().get("UpdateFailedCount").value_or(0); + int update_failed_count = params.get("UpdateFailedCount").value_or(0); if (path.contains("UpdateFailedCount") && update_failed_count > 0) { - lastUpdateTimeLbl->setText("failed to fetch update"); - updateButton->setText("CHECK"); - updateButton->setEnabled(true); + lastUpdateLbl->setText("failed to fetch update"); + updateBtn->setText("CHECK"); + updateBtn->setEnabled(true); } else if (path.contains("LastUpdateTime")) { updateLabels(); } @@ -222,79 +247,36 @@ void SoftwarePanel::showEvent(QShowEvent *event) { } void SoftwarePanel::updateLabels() { - Params params = Params(); - std::string brand = params.getBool("Passive") ? "dashcam" : "openpilot"; - QList> dev_params = { - {"Git Branch", params.get("GitBranch")}, - {"Git Commit", params.get("GitCommit").substr(0, 10)}, - {"Panda Firmware", params.get("PandaFirmwareHex")}, - {"OS Version", Hardware::get_os_version()}, - }; - - QString version = QString::fromStdString(brand + " v" + params.get("Version").substr(0, 14)).trimmed(); - QString lastUpdateTime = ""; - - std::string last_update_param = params.get("LastUpdateTime"); - if (!last_update_param.empty()){ - QDateTime lastUpdateDate = QDateTime::fromString(QString::fromStdString(last_update_param + "Z"), Qt::ISODate); - lastUpdateTime = timeAgo(lastUpdateDate); + QString lastUpdate = ""; + auto tm = params.get("LastUpdateTime"); + if (!tm.empty()) { + lastUpdate = timeAgo(QDateTime::fromString(QString::fromStdString(tm + "Z"), Qt::ISODate)); } - if (labels.size() < dev_params.size()) { - versionLbl = new LabelControl("Version", version, QString::fromStdString(params.get("ReleaseNotes")).trimmed()); - layout()->addWidget(versionLbl); - layout()->addWidget(horizontal_line()); - - lastUpdateTimeLbl = new LabelControl("Last Update Check", lastUpdateTime, "The last time openpilot successfully checked for an update. The updater only runs while the car is off."); - layout()->addWidget(lastUpdateTimeLbl); - layout()->addWidget(horizontal_line()); - - updateButton = new ButtonControl("Check for Update", "CHECK", "", [=]() { - Params params = Params(); - if (params.getBool("IsOffroad")) { - fs_watch->addPath(QString::fromStdString(params.getParamsPath()) + "/d/LastUpdateTime"); - fs_watch->addPath(QString::fromStdString(params.getParamsPath()) + "/d/UpdateFailedCount"); - updateButton->setText("CHECKING"); - updateButton->setEnabled(false); - } - std::system("pkill -1 -f selfdrive.updated"); - }, "", this); - layout()->addWidget(updateButton); - layout()->addWidget(horizontal_line()); - } else { - versionLbl->setText(version); - lastUpdateTimeLbl->setText(lastUpdateTime); - updateButton->setText("CHECK"); - updateButton->setEnabled(true); - } - - for (int i = 0; i < dev_params.size(); i++) { - const auto &[name, value] = dev_params[i]; - QString val = QString::fromStdString(value).trimmed(); - if (labels.size() > i) { - labels[i]->setText(val); - } else { - labels.push_back(new LabelControl(name, val)); - layout()->addWidget(labels[i]); - if (i < (dev_params.size() - 1)) { - layout()->addWidget(horizontal_line()); - } - } - } + versionLbl->setText(getBrandVersion()); + lastUpdateLbl->setText(lastUpdate); + updateBtn->setText("CHECK"); + updateBtn->setEnabled(true); + gitBranchLbl->setText(QString::fromStdString(params.get("GitBranch"))); + gitCommitLbl->setText(QString::fromStdString(params.get("GitCommit")).left(10)); + osVersionLbl->setText(QString::fromStdString(Hardware::get_os_version()).trimmed()); } QWidget * network_panel(QWidget * parent) { #ifdef QCOM - QVBoxLayout *layout = new QVBoxLayout; + QWidget *w = new QWidget(parent); + QVBoxLayout *layout = new QVBoxLayout(w); layout->setSpacing(30); // wifi + tethering buttons - layout->addWidget(new ButtonControl("WiFi Settings", "OPEN", "", - [=]() { HardwareEon::launch_wifi(); })); + auto wifiBtn = new ButtonControl("WiFi Settings", "OPEN"); + QObject::connect(wifiBtn, &ButtonControl::released, [=]() { HardwareEon::launch_wifi(); }); + layout->addWidget(wifiBtn); layout->addWidget(horizontal_line()); - layout->addWidget(new ButtonControl("Tethering Settings", "OPEN", "", - [=]() { HardwareEon::launch_tethering(); })); + auto tetheringBtn = new ButtonControl("Tethering Settings", "OPEN"); + QObject::connect(tetheringBtn, &ButtonControl::released, [=]() { HardwareEon::launch_tethering(); }); + layout->addWidget(tetheringBtn); layout->addWidget(horizontal_line()); // SSH key management @@ -303,9 +285,6 @@ QWidget * network_panel(QWidget * parent) { layout->addWidget(new SshControl()); layout->addStretch(1); - - QWidget *w = new QWidget; - w->setLayout(layout); #else Networking *w = new Networking(parent); #endif @@ -313,14 +292,15 @@ QWidget * network_panel(QWidget * parent) { } void SettingsWindow::showEvent(QShowEvent *event) { - if (layout()) { - panel_widget->setCurrentIndex(0); - nav_btns->buttons()[0]->setChecked(true); - return; - } + panel_widget->setCurrentIndex(0); + nav_btns->buttons()[0]->setChecked(true); +} + +SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { // setup two main layouts - QVBoxLayout *sidebar_layout = new QVBoxLayout(); + sidebar_widget = new QWidget; + QVBoxLayout *sidebar_layout = new QVBoxLayout(sidebar_widget); sidebar_layout->setMargin(0); panel_widget = new QStackedWidget(); panel_widget->setStyleSheet(R"( @@ -347,33 +327,41 @@ void SettingsWindow::showEvent(QShowEvent *event) { QObject::connect(device, &DevicePanel::reviewTrainingGuide, this, &SettingsWindow::reviewTrainingGuide); QObject::connect(device, &DevicePanel::showDriverView, this, &SettingsWindow::showDriverView); - QPair panels[] = { + QList> panels = { {"Device", device}, {"Network", network_panel(this)}, {"Toggles", new TogglesPanel(this)}, - {"Software", new SoftwarePanel()}, + {"Software", new SoftwarePanel(this)}, }; - sidebar_layout->addSpacing(45); +#ifdef ENABLE_MAPS + if (!Params().get("MapboxToken").empty()) { + auto map_panel = new MapPanel(this); + panels.push_back({"Navigation", map_panel}); + QObject::connect(map_panel, &MapPanel::closeSettings, this, &SettingsWindow::closeSettings); + } +#endif + const int padding = panels.size() > 3 ? 25 : 35; + nav_btns = new QButtonGroup(); for (auto &[name, panel] : panels) { QPushButton *btn = new QPushButton(name); btn->setCheckable(true); btn->setChecked(nav_btns->buttons().size() == 0); - btn->setStyleSheet(R"( + btn->setStyleSheet(QString(R"( QPushButton { color: grey; border: none; background: none; font-size: 65px; font-weight: 500; - padding-top: 35px; - padding-bottom: 35px; + padding-top: %1px; + padding-bottom: %1px; } QPushButton:checked { color: white; } - )"); + )").arg(padding)); nav_btns->addButton(btn); sidebar_layout->addWidget(btn, 0, Qt::AlignRight); @@ -384,21 +372,19 @@ void SettingsWindow::showEvent(QShowEvent *event) { panel_widget->addWidget(panel_frame); QObject::connect(btn, &QPushButton::released, [=, w = panel_frame]() { + btn->setChecked(true); panel_widget->setCurrentWidget(w); }); } sidebar_layout->setContentsMargins(50, 50, 100, 50); // main settings layout, sidebar + main panel - QHBoxLayout *settings_layout = new QHBoxLayout(); + QHBoxLayout *main_layout = new QHBoxLayout(this); - sidebar_widget = new QWidget; - sidebar_widget->setLayout(sidebar_layout); sidebar_widget->setFixedWidth(500); - settings_layout->addWidget(sidebar_widget); - settings_layout->addWidget(panel_widget); + main_layout->addWidget(sidebar_widget); + main_layout->addWidget(panel_widget); - setLayout(settings_layout); setStyleSheet(R"( * { color: white; @@ -410,16 +396,8 @@ void SettingsWindow::showEvent(QShowEvent *event) { )"); } -void SettingsWindow::hideEvent(QHideEvent *event){ +void SettingsWindow::hideEvent(QHideEvent *event) { #ifdef QCOM HardwareEon::close_activities(); #endif - - // TODO: this should be handled by the Dialog classes - QList children = findChildren(); - for(auto &w : children){ - if(w->metaObject()->superClass()->className() == QString("QDialog")){ - w->close(); - } - } } diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index b0ae4875b..9670d8d90 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -5,9 +5,7 @@ #include #include #include -#include #include -#include #include @@ -30,21 +28,23 @@ public: explicit TogglesPanel(QWidget *parent = nullptr); }; -class SoftwarePanel : public QFrame { +class SoftwarePanel : public QWidget { Q_OBJECT public: explicit SoftwarePanel(QWidget* parent = nullptr); -protected: - void showEvent(QShowEvent *event) override; - private: - QList labels; - LabelControl *versionLbl; - LabelControl *lastUpdateTimeLbl; - ButtonControl *updateButton; + void showEvent(QShowEvent *event) override; void updateLabels(); + LabelControl *gitBranchLbl; + LabelControl *gitCommitLbl; + LabelControl *osVersionLbl; + LabelControl *versionLbl; + LabelControl *lastUpdateLbl; + ButtonControl *updateBtn; + + Params params; QFileSystemWatcher *fs_watch; }; @@ -52,7 +52,7 @@ class SettingsWindow : public QFrame { Q_OBJECT public: - explicit SettingsWindow(QWidget *parent = 0) : QFrame(parent) {}; + explicit SettingsWindow(QWidget *parent = 0); protected: void hideEvent(QHideEvent *event) override; diff --git a/selfdrive/ui/qt/offroad/text_view.qml b/selfdrive/ui/qt/offroad/text_view.qml index c97a67616..10b423bac 100644 --- a/selfdrive/ui/qt/offroad/text_view.qml +++ b/selfdrive/ui/qt/offroad/text_view.qml @@ -2,32 +2,46 @@ import QtQuick 2.0 Item { id: root - signal qmlSignal() + signal scroll() Flickable { id: flickArea objectName: "flickArea" anchors.fill: parent contentHeight: helpText.height - contentWidth: helpText.width + contentWidth: width - (leftMargin + rightMargin) + bottomMargin: 50 + topMargin: 50 + rightMargin: 50 + leftMargin: 50 flickableDirection: Flickable.VerticalFlick flickDeceleration: 7500.0 maximumFlickVelocity: 10000.0 pixelAligned: true - onAtYEndChanged: root.qmlSignal() + onAtYEndChanged: root.scroll() Text { id: helpText - width: flickArea.width - font.pixelSize: font_size + width: flickArea.contentWidth + font.family: "Inter" + font.weight: "Light" + font.pixelSize: 50 textFormat: Text.RichText - color: "white" + color: "#C9C9C9" wrapMode: Text.Wrap - text: text_view } } + + Rectangle { + id: scrollbar + anchors.right: flickArea.right + anchors.rightMargin: 20 + y: flickArea.topMargin + flickArea.visibleArea.yPosition * (flickArea.height - flickArea.bottomMargin - flickArea.topMargin) + width: 12 + radius: 6 + height: flickArea.visibleArea.heightRatio * (flickArea.height - flickArea.bottomMargin - flickArea.topMargin) + color: "#808080" + } } - - diff --git a/selfdrive/ui/qt/offroad/wifiManager.cc b/selfdrive/ui/qt/offroad/wifiManager.cc index 7ffaccb1c..06a51990b 100644 --- a/selfdrive/ui/qt/offroad/wifiManager.cc +++ b/selfdrive/ui/qt/offroad/wifiManager.cc @@ -1,48 +1,12 @@ -#include "wifiManager.h" - -#include +#include "selfdrive/ui/qt/offroad/wifiManager.h" #include #include +#include #include "selfdrive/common/params.h" #include "selfdrive/common/swaglog.h" -/** - * We are using a NetworkManager DBUS API : https://developer.gnome.org/NetworkManager/1.26/spec.html - * */ - -// https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApFlags -const int NM_802_11_AP_FLAGS_PRIVACY = 0x00000001; - -// https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApSecurityFlags -const int NM_802_11_AP_SEC_PAIR_WEP40 = 0x00000001; -const int NM_802_11_AP_SEC_PAIR_WEP104 = 0x00000002; -const int NM_802_11_AP_SEC_GROUP_WEP40 = 0x00000010; -const int NM_802_11_AP_SEC_GROUP_WEP104 = 0x00000020; -const int NM_802_11_AP_SEC_KEY_MGMT_PSK = 0x00000100; -const int NM_802_11_AP_SEC_KEY_MGMT_802_1X = 0x00000200; - -const QString nm_path = "/org/freedesktop/NetworkManager"; -const QString nm_settings_path = "/org/freedesktop/NetworkManager/Settings"; - -const QString nm_iface = "org.freedesktop.NetworkManager"; -const QString props_iface = "org.freedesktop.DBus.Properties"; -const QString nm_settings_iface = "org.freedesktop.NetworkManager.Settings"; -const QString nm_settings_conn_iface = "org.freedesktop.NetworkManager.Settings.Connection"; -const QString device_iface = "org.freedesktop.NetworkManager.Device"; -const QString wireless_device_iface = "org.freedesktop.NetworkManager.Device.Wireless"; -const QString ap_iface = "org.freedesktop.NetworkManager.AccessPoint"; -const QString connection_iface = "org.freedesktop.NetworkManager.Connection.Active"; -const QString ipv4config_iface = "org.freedesktop.NetworkManager.IP4Config"; - -const QString nm_service = "org.freedesktop.NetworkManager"; - -const int state_connected = 100; -const int state_need_auth = 60; -const int reason_wrong_password = 8; -const int dbus_timeout = 100; - template T get_response(QDBusMessage response) { QVariant first = response.arguments().at(0); @@ -64,76 +28,111 @@ bool compare_by_strength(const Network &a, const Network &b) { return a.strength > b.strength; } -WifiManager::WifiManager(QWidget* parent) { +WifiManager::WifiManager(QWidget* parent) : QWidget(parent) { qDBusRegisterMetaType(); qDBusRegisterMetaType(); connecting_to_network = ""; - adapter = get_adapter(); - - bool has_adapter = adapter != ""; - if (!has_adapter){ - throw std::runtime_error("Error connecting to NetworkManager"); - } - - QDBusInterface nm(nm_service, adapter, device_iface, bus); - bus.connect(nm_service, adapter, device_iface, "StateChanged", this, SLOT(change(unsigned int, unsigned int, unsigned int))); - - QDBusInterface device_props(nm_service, adapter, props_iface, bus); - device_props.setTimeout(dbus_timeout); - QDBusMessage response = device_props.call("Get", device_iface, "State"); - raw_adapter_state = get_response(response); - change(raw_adapter_state, 0, 0); // Set tethering ssid as "weedle" + first 4 characters of a dongle id tethering_ssid = "weedle"; std::string bytes = Params().get("DongleId"); if (bytes.length() >= 4) { - tethering_ssid+="-"+QString::fromStdString(bytes.substr(0,4)); + tethering_ssid += "-" + QString::fromStdString(bytes.substr(0,4)); } - // Create dbus interface for tethering button. This populates the introspection cache, - // making sure all future creations are non-blocking - // https://bugreports.qt.io/browse/QTBUG-14485 - QDBusInterface(nm_service, nm_settings_path, nm_settings_iface, bus); + adapter = getAdapter(); + if (!adapter.isEmpty()) { + setup(); + } else { + bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, "DeviceAdded", this, SLOT(deviceAdded(QDBusObjectPath))); + } + + QTimer* timer = new QTimer(this); + QObject::connect(timer, &QTimer::timeout, this, [=]() { + if (!adapter.isEmpty() && this->isVisible()) { + requestScan(); + } + }); + timer->start(5000); +} + +void WifiManager::setup() { + QDBusInterface nm(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE, bus); + bus.connect(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE, "StateChanged", this, SLOT(stateChange(unsigned int, unsigned int, unsigned int))); + bus.connect(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, "PropertiesChanged", this, SLOT(propertyChange(QString, QVariantMap, QStringList))); + + bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "ConnectionRemoved", this, SLOT(connectionRemoved(QDBusObjectPath))); + bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "NewConnection", this, SLOT(newConnection(QDBusObjectPath))); + + QDBusInterface device_props(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, bus); + device_props.setTimeout(DBUS_TIMEOUT); + QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_DEVICE, "State"); + raw_adapter_state = get_response(response); + + initActiveAp(); + initConnections(); + requestScan(); } void WifiManager::refreshNetworks() { + if (adapter.isEmpty()) { + return; + } seen_networks.clear(); seen_ssids.clear(); ipv4_address = get_ipv4_address(); - for (Network &network : get_networks()) { - if (seen_ssids.count(network.ssid)) { + + QDBusInterface nm(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, bus); + nm.setTimeout(DBUS_TIMEOUT); + + const QDBusReply> &response = nm.call("GetAllAccessPoints"); + for (const QDBusObjectPath &path : response.value()) { + QByteArray ssid = get_property(path.path(), "Ssid"); + if (ssid.isEmpty() || seen_ssids.contains(ssid)) { continue; } - seen_ssids.push_back(network.ssid); + unsigned int strength = get_ap_strength(path.path()); + SecurityType security = getSecurityType(path.path()); + ConnectedType ctype; + if (path.path() != activeAp) { + ctype = ConnectedType::DISCONNECTED; + } else { + if (ssid == connecting_to_network) { + ctype = ConnectedType::CONNECTING; + } else { + ctype = ConnectedType::CONNECTED; + } + } + Network network = {path.path(), ssid, strength, ctype, security}; + seen_ssids.push_back(ssid); seen_networks.push_back(network); } - + std::sort(seen_networks.begin(), seen_networks.end(), compare_by_strength); } -QString WifiManager::get_ipv4_address(){ - if (raw_adapter_state != state_connected){ +QString WifiManager::get_ipv4_address() { + if (raw_adapter_state != NM_DEVICE_STATE_ACTIVATED) { return ""; } QVector conns = get_active_connections(); - for (auto &p : conns){ + for (auto &p : conns) { QString active_connection = p.path(); - QDBusInterface nm(nm_service, active_connection, props_iface, bus); - nm.setTimeout(dbus_timeout); + QDBusInterface nm(NM_DBUS_SERVICE, active_connection, NM_DBUS_INTERFACE_PROPERTIES, bus); + nm.setTimeout(DBUS_TIMEOUT); - QDBusObjectPath pth = get_response(nm.call("Get", connection_iface, "Ip4Config")); + QDBusObjectPath pth = get_response(nm.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Ip4Config")); QString ip4config = pth.path(); - QString type = get_response(nm.call("Get", connection_iface, "Type")); + QString type = get_response(nm.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type")); if (type == "802-11-wireless") { - QDBusInterface nm2(nm_service, ip4config, props_iface, bus); - nm2.setTimeout(dbus_timeout); + QDBusInterface nm2(NM_DBUS_SERVICE, ip4config, NM_DBUS_INTERFACE_PROPERTIES, bus); + nm2.setTimeout(DBUS_TIMEOUT); - const QDBusArgument &arr = get_response(nm2.call("Get", ipv4config_iface, "AddressData")); + const QDBusArgument &arr = get_response(nm2.call("Get", NM_DBUS_INTERFACE_IP4_CONFIG, "AddressData")); QMap pth2; arr.beginArray(); - while (!arr.atEnd()){ + while (!arr.atEnd()) { arr >> pth2; QString ipv4 = pth2.value("address").value(); arr.endArray(); @@ -145,47 +144,7 @@ QString WifiManager::get_ipv4_address(){ return ""; } -QList WifiManager::get_networks() { - QList r; - QDBusInterface nm(nm_service, adapter, wireless_device_iface, bus); - nm.setTimeout(dbus_timeout); - - QDBusMessage response = nm.call("GetAllAccessPoints"); - QVariant first = response.arguments().at(0); - - QString active_ap = get_active_ap(); - const QDBusArgument &args = first.value(); - args.beginArray(); - while (!args.atEnd()) { - QDBusObjectPath path; - args >> path; - - QByteArray ssid = get_property(path.path(), "Ssid"); - unsigned int strength = get_ap_strength(path.path()); - SecurityType security = getSecurityType(path.path()); - ConnectedType ctype; - if (path.path() != active_ap) { - ctype = ConnectedType::DISCONNECTED; - } else { - if (ssid == connecting_to_network) { - ctype = ConnectedType::CONNECTING; - } else { - ctype = ConnectedType::CONNECTED; - } - } - Network network = {path.path(), ssid, strength, ctype, security}; - - if (ssid.length()) { - r.push_back(network); - } - } - args.endArray(); - - std::sort(r.begin(), r.end(), compare_by_strength); - return r; -} - -SecurityType WifiManager::getSecurityType(QString path) { +SecurityType WifiManager::getSecurityType(const QString &path) { int sflag = get_property(path, "Flags").toInt(); int wpaflag = get_property(path, "WpaFlags").toInt(); int rsnflag = get_property(path, "RsnFlags").toInt(); @@ -194,31 +153,32 @@ SecurityType WifiManager::getSecurityType(QString path) { // obtained by looking at flags of networks in the office as reported by an Android phone const int supports_wpa = NM_802_11_AP_SEC_PAIR_WEP40 | NM_802_11_AP_SEC_PAIR_WEP104 | NM_802_11_AP_SEC_GROUP_WEP40 | NM_802_11_AP_SEC_GROUP_WEP104 | NM_802_11_AP_SEC_KEY_MGMT_PSK; - if (sflag == 0) { + if ((sflag == NM_802_11_AP_FLAGS_NONE) || ((sflag & NM_802_11_AP_FLAGS_WPS) && !(wpa_props & supports_wpa))) { return SecurityType::OPEN; } else if ((sflag & NM_802_11_AP_FLAGS_PRIVACY) && (wpa_props & supports_wpa) && !(wpa_props & NM_802_11_AP_SEC_KEY_MGMT_802_1X)) { return SecurityType::WPA; } else { + LOGW("Unsupported network! sflag: %d, wpaflag: %d, rsnflag: %d", sflag, wpaflag, rsnflag); return SecurityType::UNSUPPORTED; } } -void WifiManager::connect(Network n) { +void WifiManager::connect(const Network &n) { return connect(n, "", ""); } -void WifiManager::connect(Network n, QString password) { +void WifiManager::connect(const Network &n, const QString &password) { return connect(n, "", password); } -void WifiManager::connect(Network n, QString username, QString password) { +void WifiManager::connect(const Network &n, const QString &username, const QString &password) { connecting_to_network = n.ssid; // disconnect(); - clear_connections(n.ssid); //Clear all connections that may already exist to the network we are connecting + forgetConnection(n.ssid); //Clear all connections that may already exist to the network we are connecting connect(n.ssid, username, password, n.security_type); } -void WifiManager::connect(QByteArray ssid, QString username, QString password, SecurityType security_type) { +void WifiManager::connect(const QByteArray &ssid, const QString &username, const QString &password, SecurityType security_type) { Connection connection; connection["connection"]["type"] = "802-11-wireless"; connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}'); @@ -237,36 +197,35 @@ void WifiManager::connect(QByteArray ssid, QString username, QString password, S connection["ipv4"]["method"] = "auto"; connection["ipv6"]["method"] = "ignore"; - QDBusInterface nm_settings(nm_service, nm_settings_path, nm_settings_iface, bus); - nm_settings.setTimeout(dbus_timeout); + QDBusInterface nm_settings(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, bus); + nm_settings.setTimeout(DBUS_TIMEOUT); nm_settings.call("AddConnection", QVariant::fromValue(connection)); - activate_wifi_connection(QString(ssid)); } -void WifiManager::deactivate_connections(QString ssid) { +void WifiManager::deactivateConnection(const QString &ssid) { for (QDBusObjectPath active_connection_raw : get_active_connections()) { QString active_connection = active_connection_raw.path(); - QDBusInterface nm(nm_service, active_connection, props_iface, bus); - nm.setTimeout(dbus_timeout); + QDBusInterface nm(NM_DBUS_SERVICE, active_connection, NM_DBUS_INTERFACE_PROPERTIES, bus); + nm.setTimeout(DBUS_TIMEOUT); - QDBusObjectPath pth = get_response(nm.call("Get", connection_iface, "SpecificObject")); + QDBusObjectPath pth = get_response(nm.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "SpecificObject")); if (pth.path() != "" && pth.path() != "/") { QString Ssid = get_property(pth.path(), "Ssid"); if (Ssid == ssid) { - QDBusInterface nm2(nm_service, nm_path, nm_iface, bus); - nm2.setTimeout(dbus_timeout); - nm2.call("DeactivateConnection", QVariant::fromValue(active_connection_raw));// TODO change to disconnect + QDBusInterface nm2(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, bus); + nm2.setTimeout(DBUS_TIMEOUT); + nm2.call("DeactivateConnection", QVariant::fromValue(active_connection_raw)); } } } } QVector WifiManager::get_active_connections() { - QDBusInterface nm(nm_service, nm_path, props_iface, bus); - nm.setTimeout(dbus_timeout); + QDBusInterface nm(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE_PROPERTIES, bus); + nm.setTimeout(DBUS_TIMEOUT); - QDBusMessage response = nm.call("Get", nm_iface, "ActiveConnections"); + QDBusMessage response = nm.call("Get", NM_DBUS_INTERFACE, "ActiveConnections"); const QDBusArgument &arr = get_response(response); QVector conns; @@ -280,194 +239,159 @@ QVector WifiManager::get_active_connections() { return conns; } -void WifiManager::clear_connections(QString ssid) { - for(QDBusObjectPath path : list_connections()){ - QDBusInterface nm2(nm_service, path.path(), nm_settings_conn_iface, bus); - nm2.setTimeout(dbus_timeout); +bool WifiManager::isKnownConnection(const QString &ssid) { + return !getConnectionPath(ssid).path().isEmpty(); +} - QDBusMessage response = nm2.call("GetSettings"); - - const QDBusArgument &dbusArg = response.arguments().at(0).value(); - - QMap> map; - dbusArg >> map; - for (auto &inner : map) { - for (auto &val : inner) { - QString key = inner.key(val); - if (key == "ssid") { - if (val == ssid) { - nm2.call("Delete"); - } - } - } - } +void WifiManager::forgetConnection(const QString &ssid) { + const QDBusObjectPath &path = getConnectionPath(ssid); + if (!path.path().isEmpty()) { + QDBusInterface nm2(NM_DBUS_SERVICE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); + nm2.call("Delete"); } } -void WifiManager::request_scan() { - QDBusInterface nm(nm_service, adapter, wireless_device_iface, bus); - nm.setTimeout(dbus_timeout); - nm.call("RequestScan", QVariantMap()); +bool WifiManager::isWirelessAdapter(const QDBusObjectPath &path) { + QDBusInterface device_props(NM_DBUS_SERVICE, path.path(), NM_DBUS_INTERFACE_PROPERTIES, bus); + device_props.setTimeout(DBUS_TIMEOUT); + const uint deviceType = get_response(device_props.call("Get", NM_DBUS_INTERFACE_DEVICE, "DeviceType")); + return deviceType == NM_DEVICE_TYPE_WIFI; +} + +void WifiManager::requestScan() { + QDBusInterface nm(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, bus); + nm.setTimeout(DBUS_TIMEOUT); + nm.call("RequestScan", QVariantMap()); } uint WifiManager::get_wifi_device_state() { - QDBusInterface device_props(nm_service, adapter, props_iface, bus); - device_props.setTimeout(dbus_timeout); + QDBusInterface device_props(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, bus); + device_props.setTimeout(DBUS_TIMEOUT); - QDBusMessage response = device_props.call("Get", device_iface, "State"); + QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_DEVICE, "State"); uint resp = get_response(response); return resp; } -QString WifiManager::get_active_ap() { - QDBusInterface device_props(nm_service, adapter, props_iface, bus); - device_props.setTimeout(dbus_timeout); +QByteArray WifiManager::get_property(const QString &network_path , const QString &property) { + QDBusInterface device_props(NM_DBUS_SERVICE, network_path, NM_DBUS_INTERFACE_PROPERTIES, bus); + device_props.setTimeout(DBUS_TIMEOUT); - QDBusMessage response = device_props.call("Get", wireless_device_iface, "ActiveAccessPoint"); - QDBusObjectPath r = get_response(response); - return r.path(); -} - -QByteArray WifiManager::get_property(QString network_path ,QString property) { - QDBusInterface device_props(nm_service, network_path, props_iface, bus); - device_props.setTimeout(dbus_timeout); - - QDBusMessage response = device_props.call("Get", ap_iface, property); + QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_ACCESS_POINT, property); return get_response(response); } -unsigned int WifiManager::get_ap_strength(QString network_path) { - QDBusInterface device_props(nm_service, network_path, props_iface, bus); - device_props.setTimeout(dbus_timeout); +unsigned int WifiManager::get_ap_strength(const QString &network_path) { + QDBusInterface device_props(NM_DBUS_SERVICE, network_path, NM_DBUS_INTERFACE_PROPERTIES, bus); + device_props.setTimeout(DBUS_TIMEOUT); - QDBusMessage response = device_props.call("Get", ap_iface, "Strength"); + QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_ACCESS_POINT, "Strength"); return get_response(response); } -QString WifiManager::get_adapter() { - QDBusInterface nm(nm_service, nm_path, nm_iface, bus); - nm.setTimeout(dbus_timeout); +QString WifiManager::getAdapter() { + QDBusInterface nm(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, bus); + nm.setTimeout(DBUS_TIMEOUT); - QDBusMessage response = nm.call("GetDevices"); - QVariant first = response.arguments().at(0); - - QString adapter_path = ""; - - const QDBusArgument &args = first.value(); - args.beginArray(); - while (!args.atEnd()) { - QDBusObjectPath path; - args >> path; - - // Get device type - QDBusInterface device_props(nm_service, path.path(), props_iface, bus); - device_props.setTimeout(dbus_timeout); - - QDBusMessage response = device_props.call("Get", device_iface, "DeviceType"); - uint device_type = get_response(response); - - if (device_type == 2) { // Wireless - adapter_path = path.path(); - break; + const QDBusReply> &response = nm.call("GetDevices"); + for (const QDBusObjectPath &path : response.value()) { + if (isWirelessAdapter(path)) { + return path.path(); } } - args.endArray(); - - return adapter_path; + return ""; } -void WifiManager::change(unsigned int new_state, unsigned int previous_state, unsigned int change_reason) { +void WifiManager::stateChange(unsigned int new_state, unsigned int previous_state, unsigned int change_reason) { raw_adapter_state = new_state; - if (new_state == state_need_auth && change_reason == reason_wrong_password) { + if (new_state == NM_DEVICE_STATE_NEED_AUTH && change_reason == NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT) { + knownConnections.remove(getConnectionPath(connecting_to_network)); emit wrongPassword(connecting_to_network); - } else if (new_state == state_connected) { - emit successfulConnection(connecting_to_network); + } else if (new_state == NM_DEVICE_STATE_ACTIVATED) { connecting_to_network = ""; + if (this->isVisible()) { + refreshNetworks(); + emit refreshSignal(); + } + } +} + +// https://developer.gnome.org/NetworkManager/stable/gdbus-org.freedesktop.NetworkManager.Device.Wireless.html +void WifiManager::propertyChange(const QString &interface, const QVariantMap &props, const QStringList &invalidated_props) { + if (interface == NM_DBUS_INTERFACE_DEVICE_WIRELESS && props.contains("LastScan")) { + if (this->isVisible() || firstScan) { + refreshNetworks(); + emit refreshSignal(); + firstScan = false; + } + } else if (interface == NM_DBUS_INTERFACE_DEVICE_WIRELESS && props.contains("ActiveAccessPoint")) { + const QDBusObjectPath &path = props.value("ActiveAccessPoint").value(); + activeAp = path.path(); + } +} + +void WifiManager::deviceAdded(const QDBusObjectPath &path) { + if (isWirelessAdapter(path) && (adapter.isEmpty() || adapter == "/")) { + adapter = path.path(); + setup(); + } +} + +void WifiManager::connectionRemoved(const QDBusObjectPath &path) { + knownConnections.remove(path); +} + +void WifiManager::newConnection(const QDBusObjectPath &path) { + knownConnections[path] = getConnectionSsid(path); + if (knownConnections[path] != tethering_ssid) { + activateWifiConnection(knownConnections[path]); } } void WifiManager::disconnect() { - QString active_ap = get_active_ap(); - if (active_ap != "" && active_ap != "/") { - deactivate_connections(get_property(active_ap, "Ssid")); + if (activeAp != "" && activeAp != "/") { + deactivateConnection(get_property(activeAp, "Ssid")); } } -QVector WifiManager::list_connections(){ - QVector connections; - QDBusInterface nm(nm_service, nm_settings_path, nm_settings_iface, bus); - nm.setTimeout(dbus_timeout); - - QDBusMessage response = nm.call("ListConnections"); - QVariant first = response.arguments().at(0); - const QDBusArgument &args = first.value(); - args.beginArray(); - while (!args.atEnd()) { - QDBusObjectPath path; - args >> path; - connections.push_back(path); - } - return connections; -} - -bool WifiManager::activate_wifi_connection(QString ssid){ - QString devicePath = get_adapter(); - - for(QDBusObjectPath path : list_connections()){ - QDBusInterface nm2(nm_service, path.path(), nm_settings_conn_iface, bus); - nm2.setTimeout(dbus_timeout); - - QDBusMessage response = nm2.call("GetSettings"); - const QDBusArgument &dbusArg = response.arguments().at(0).value(); - - QMap> map; - dbusArg >> map; - for (auto &inner : map) { - for (auto &val : inner) { - QString key = inner.key(val); - if (key == "ssid") { - if (val == ssid) { - QDBusInterface nm3(nm_service, nm_path, nm_iface, bus); - nm3.setTimeout(dbus_timeout); - nm3.call("ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(devicePath)), QVariant::fromValue(QDBusObjectPath("/"))); - return true; - } - } - } +QDBusObjectPath WifiManager::getConnectionPath(const QString &ssid) { + for (const QString &conn_ssid : knownConnections) { + if (ssid == conn_ssid) { + return knownConnections.key(conn_ssid); } } - return false; + return QDBusObjectPath(); } -//Functions for tethering -bool WifiManager::activate_tethering_connection(){ - QString devicePath = get_adapter(); - for(QDBusObjectPath path : list_connections()){ - QDBusInterface nm2(nm_service, path.path(), nm_settings_conn_iface, bus); - nm2.setTimeout(dbus_timeout); +QString WifiManager::getConnectionSsid(const QDBusObjectPath &path) { + QDBusInterface nm(NM_DBUS_SERVICE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); + nm.setTimeout(DBUS_TIMEOUT); + const QDBusReply result = nm.call("GetSettings"); + return result.value().value("802-11-wireless").value("ssid").toString(); +} - QDBusMessage response = nm2.call("GetSettings"); - const QDBusArgument &dbusArg = response.arguments().at(0).value(); +void WifiManager::initConnections() { + QDBusInterface nm(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, bus); + nm.setTimeout(DBUS_TIMEOUT); - QMap> map; - dbusArg >> map; - for (auto &inner : map) { - for (auto &val : inner) { - QString key = inner.key(val); - if (key == "ssid") { - if (val == tethering_ssid.toUtf8()) { - QDBusInterface nm3(nm_service, nm_path, nm_iface, bus); - nm3.setTimeout(dbus_timeout); - nm3.call("ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(devicePath)), QVariant::fromValue(QDBusObjectPath("/"))); - return true; - } - } - } - } + const QDBusReply> response = nm.call("ListConnections"); + for (const QDBusObjectPath &path : response.value()) { + knownConnections[path] = getConnectionSsid(path); } - return false; } -void WifiManager::addTetheringConnection(){ + +void WifiManager::activateWifiConnection(const QString &ssid) { + const QDBusObjectPath &path = getConnectionPath(ssid); + if (!path.path().isEmpty()) { + connecting_to_network = ssid; + QDBusInterface nm3(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, bus); + nm3.setTimeout(DBUS_TIMEOUT); + nm3.call("ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(adapter)), QVariant::fromValue(QDBusObjectPath("/"))); + } +} + +// Functions for tethering +void WifiManager::addTetheringConnection() { Connection connection; connection["connection"]["id"] = "Hotspot"; connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}'); @@ -483,7 +407,7 @@ void WifiManager::addTetheringConnection(){ connection["802-11-wireless-security"]["key-mgmt"] = "wpa-psk"; connection["802-11-wireless-security"]["pairwise"] = QStringList("ccmp"); connection["802-11-wireless-security"]["proto"] = QStringList("rsn"); - connection["802-11-wireless-security"]["psk"] = tetheringPassword; + connection["802-11-wireless-security"]["psk"] = defaultTetheringPassword; connection["ipv4"]["method"] = "shared"; QMap address; @@ -491,32 +415,68 @@ void WifiManager::addTetheringConnection(){ address["prefix"] = 24u; connection["ipv4"]["address-data"] = QVariant::fromValue(IpConfig() << address); connection["ipv4"]["gateway"] = "192.168.43.1"; + connection["ipv4"]["route-metric"] = 1100; connection["ipv6"]["method"] = "ignore"; - QDBusInterface nm_settings(nm_service, nm_settings_path, nm_settings_iface, bus); - nm_settings.setTimeout(dbus_timeout); + QDBusInterface nm_settings(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, bus); + nm_settings.setTimeout(DBUS_TIMEOUT); nm_settings.call("AddConnection", QVariant::fromValue(connection)); } -void WifiManager::enableTethering() { - if(activate_tethering_connection()){ - return; +void WifiManager::setTetheringEnabled(bool enabled) { + if (enabled) { + if (!isKnownConnection(tethering_ssid)) { + addTetheringConnection(); + } + activateWifiConnection(tethering_ssid); + } else { + deactivateConnection(tethering_ssid); } - addTetheringConnection(); - activate_tethering_connection(); } -void WifiManager::disableTethering() { - deactivate_connections(tethering_ssid.toUtf8()); +void WifiManager::initActiveAp() { + QDBusInterface device_props(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, bus); + device_props.setTimeout(DBUS_TIMEOUT); + + const QDBusMessage &response = device_props.call("Get", NM_DBUS_INTERFACE_DEVICE_WIRELESS, "ActiveAccessPoint"); + activeAp = get_response(response).path(); } -bool WifiManager::tetheringEnabled() { - QString active_ap = get_active_ap(); - return get_property(active_ap, "Ssid") == tethering_ssid; + +bool WifiManager::isTetheringEnabled() { + if (activeAp != "" && activeAp != "/") { + return get_property(activeAp, "Ssid") == tethering_ssid; + } + return false; } -void WifiManager::changeTetheringPassword(QString newPassword){ - tetheringPassword = newPassword; - clear_connections(tethering_ssid.toUtf8()); - addTetheringConnection(); +QString WifiManager::getTetheringPassword() { + if (!isKnownConnection(tethering_ssid)) { + addTetheringConnection(); + } + const QDBusObjectPath &path = getConnectionPath(tethering_ssid); + if (!path.path().isEmpty()) { + QDBusInterface nm(NM_DBUS_INTERFACE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); + nm.setTimeout(DBUS_TIMEOUT); + + const QDBusReply>> response = nm.call("GetSecrets", "802-11-wireless-security"); + return response.value().value("802-11-wireless-security").value("psk").toString(); + } + return ""; +} + +void WifiManager::changeTetheringPassword(const QString &newPassword) { + const QDBusObjectPath &path = getConnectionPath(tethering_ssid); + if (!path.path().isEmpty()) { + QDBusInterface nm(NM_DBUS_INTERFACE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); + nm.setTimeout(DBUS_TIMEOUT); + + Connection settings = QDBusReply(nm.call("GetSettings")).value(); + settings["802-11-wireless-security"]["psk"] = newPassword; + nm.call("Update", QVariant::fromValue(settings)); + + if (isTetheringEnabled()) { + activateWifiConnection(tethering_ssid); + } + } } diff --git a/selfdrive/ui/qt/offroad/wifiManager.h b/selfdrive/ui/qt/offroad/wifiManager.h index bbbe2e3ed..e6741ec8f 100644 --- a/selfdrive/ui/qt/offroad/wifiManager.h +++ b/selfdrive/ui/qt/offroad/wifiManager.h @@ -1,7 +1,9 @@ #pragma once -#include #include +#include + +#include "selfdrive/ui/qt/offroad/networkmanager.h" enum class SecurityType { OPEN, @@ -30,53 +32,63 @@ class WifiManager : public QWidget { public: explicit WifiManager(QWidget* parent); - void request_scan(); + void requestScan(); QVector seen_networks; + QMap knownConnections; QString ipv4_address; void refreshNetworks(); - void connect(Network ssid); - void connect(Network ssid, QString password); - void connect(Network ssid, QString username, QString password); + void forgetConnection(const QString &ssid); + bool isKnownConnection(const QString &ssid); + void activateWifiConnection(const QString &ssid); + + void connect(const Network &ssid); + void connect(const Network &ssid, const QString &password); + void connect(const Network &ssid, const QString &username, const QString &password); void disconnect(); // Tethering functions - void enableTethering(); - void disableTethering(); - bool tetheringEnabled(); - - bool activate_tethering_connection(); + void setTetheringEnabled(bool enabled); + bool isTetheringEnabled(); void addTetheringConnection(); - bool activate_wifi_connection(QString ssid); - void changeTetheringPassword(QString newPassword); + void changeTetheringPassword(const QString &newPassword); + QString getTetheringPassword(); private: QVector seen_ssids; - QString adapter;//Path to network manager wifi-device + QString adapter; // Path to network manager wifi-device QDBusConnection bus = QDBusConnection::systemBus(); - unsigned int raw_adapter_state;//Connection status https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NMDeviceState + unsigned int raw_adapter_state; // Connection status https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NMDeviceState QString connecting_to_network; QString tethering_ssid; - QString tetheringPassword = "swagswagcommma"; + const QString defaultTetheringPassword = "swagswagcomma"; - QString get_adapter(); + bool firstScan = true; + QString getAdapter(); + bool isWirelessAdapter(const QDBusObjectPath &path); QString get_ipv4_address(); - QList get_networks(); - void connect(QByteArray ssid, QString username, QString password, SecurityType security_type); - QString get_active_ap(); - void deactivate_connections(QString ssid); - void clear_connections(QString ssid); + void connect(const QByteArray &ssid, const QString &username, const QString &password, SecurityType security_type); + QString activeAp; + void initActiveAp(); + void deactivateConnection(const QString &ssid); QVector get_active_connections(); uint get_wifi_device_state(); - QByteArray get_property(QString network_path, QString property); - unsigned int get_ap_strength(QString network_path); - SecurityType getSecurityType(QString ssid); - QVector list_connections(); + QByteArray get_property(const QString &network_path, const QString &property); + unsigned int get_ap_strength(const QString &network_path); + SecurityType getSecurityType(const QString &path); + QDBusObjectPath getConnectionPath(const QString &ssid); + void initConnections(); + QString getConnectionSsid(const QDBusObjectPath &path); + void setup(); + +signals: + void wrongPassword(const QString &ssid); + void refreshSignal(); private slots: - void change(unsigned int new_state, unsigned int previous_state, unsigned int change_reason); -signals: - void wrongPassword(QString ssid); - void successfulConnection(QString ssid); - void refresh(); + void stateChange(unsigned int new_state, unsigned int previous_state, unsigned int change_reason); + void propertyChange(const QString &interface, const QVariantMap &props, const QStringList &invalidated_props); + void deviceAdded(const QDBusObjectPath &path); + void connectionRemoved(const QDBusObjectPath &path); + void newConnection(const QDBusObjectPath &path); }; diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index e26aff7bc..296f063e8 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -1,6 +1,7 @@ #include "selfdrive/ui/qt/onroad.h" #include +#include #include "selfdrive/common/swaglog.h" #include "selfdrive/common/timing.h" @@ -12,34 +13,31 @@ #endif OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { - layout = new QStackedLayout(this); - layout->setStackingMode(QStackedLayout::StackAll); + main_layout = new QStackedLayout(this); + main_layout->setStackingMode(QStackedLayout::StackAll); // old UI on bottom nvg = new NvgWindow(this); QObject::connect(this, &OnroadWindow::update, nvg, &NvgWindow::update); - split = new QHBoxLayout(); + QWidget * split_wrapper = new QWidget; + split = new QHBoxLayout(split_wrapper); split->setContentsMargins(0, 0, 0, 0); split->setSpacing(0); split->addWidget(nvg); - - QWidget * split_wrapper = new QWidget; - split_wrapper->setLayout(split); - layout->addWidget(split_wrapper); + main_layout->addWidget(split_wrapper); alerts = new OnroadAlerts(this); alerts->setAttribute(Qt::WA_TransparentForMouseEvents, true); QObject::connect(this, &OnroadWindow::update, alerts, &OnroadAlerts::updateState); QObject::connect(this, &OnroadWindow::offroadTransitionSignal, alerts, &OnroadAlerts::offroadTransition); QObject::connect(this, &OnroadWindow::offroadTransitionSignal, this, &OnroadWindow::offroadTransition); - layout->addWidget(alerts); + main_layout->addWidget(alerts); // setup stacking order alerts->raise(); - setLayout(layout); setAttribute(Qt::WA_OpaquePaintEvent); } @@ -48,9 +46,11 @@ void OnroadWindow::offroadTransition(bool offroad) { #ifdef ENABLE_MAPS if (!offroad) { QString token = QString::fromStdString(Params().get("MapboxToken")); - if (map == nullptr && !token.isEmpty()){ + if (map == nullptr && !token.isEmpty()) { QMapboxGLSettings settings; - settings.setCacheDatabasePath("/data/mbgl-cache.db"); + if (!Hardware::PC()) { + settings.setCacheDatabasePath("/data/mbgl-cache.db"); + } settings.setCacheDatabaseMaximumSize(20 * 1024 * 1024); settings.setAccessToken(token.trimmed()); @@ -68,9 +68,19 @@ void OnroadWindow::offroadTransition(bool offroad) { // ***** onroad widgets ***** OnroadAlerts::OnroadAlerts(QWidget *parent) : QWidget(parent) { - for (auto &kv : sound_map) { - auto path = QUrl::fromLocalFile(kv.second.first); - sounds[kv.first].setSource(path); + std::tuple sound_list[] = { + {AudibleAlert::CHIME_DISENGAGE, "../assets/sounds/disengaged.wav", false}, + {AudibleAlert::CHIME_ENGAGE, "../assets/sounds/engaged.wav", false}, + {AudibleAlert::CHIME_WARNING1, "../assets/sounds/warning_1.wav", false}, + {AudibleAlert::CHIME_WARNING2, "../assets/sounds/warning_2.wav", false}, + {AudibleAlert::CHIME_WARNING2_REPEAT, "../assets/sounds/warning_2.wav", true}, + {AudibleAlert::CHIME_WARNING_REPEAT, "../assets/sounds/warning_repeat.wav", true}, + {AudibleAlert::CHIME_ERROR, "../assets/sounds/error.wav", false}, + {AudibleAlert::CHIME_PROMPT, "../assets/sounds/error.wav", false}}; + + for (auto &[alert, fn, loops] : sound_list) { + sounds[alert].first.setSource(QUrl::fromLocalFile(fn)); + sounds[alert].second = loops ? QSoundEffect::Infinite : 0; } } @@ -114,7 +124,7 @@ void OnroadAlerts::offroadTransition(bool offroad) { void OnroadAlerts::updateAlert(const QString &t1, const QString &t2, float blink_rate, const std::string &type, cereal::ControlsState::AlertSize size, AudibleAlert sound) { - if (alert_type.compare(type) == 0 && text1.compare(t1) == 0) { + if (alert_type.compare(type) == 0 && text1.compare(t1) == 0 && text2.compare(t2) == 0) { return; } @@ -133,24 +143,23 @@ void OnroadAlerts::updateAlert(const QString &t1, const QString &t2, float blink } void OnroadAlerts::playSound(AudibleAlert alert) { - int loops = sound_map[alert].second ? QSoundEffect::Infinite : 0; - sounds[alert].setLoopCount(loops); - sounds[alert].setVolume(volume); - sounds[alert].play(); + auto &[sound, loops] = sounds[alert]; + sound.setLoopCount(loops); + sound.setVolume(volume); + sound.play(); } void OnroadAlerts::stopSounds() { for (auto &kv : sounds) { // Only stop repeating sounds - if (kv.second.loopsRemaining() == QSoundEffect::Infinite) { - kv.second.stop(); + auto &[sound, loops] = kv.second; + if (sound.loopsRemaining() == QSoundEffect::Infinite) { + sound.stop(); } } } void OnroadAlerts::paintEvent(QPaintEvent *event) { - QPainter p(this); - if (alert_size == cereal::ControlsState::AlertSize::NONE) { return; } @@ -162,9 +171,11 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { int h = alert_sizes[alert_size]; QRect r = QRect(0, height() - h, width(), h); + QPainter p(this); + // draw background + gradient p.setPen(Qt::NoPen); - p.setCompositionMode(QPainter::CompositionMode_DestinationOver); + p.setCompositionMode(QPainter::CompositionMode_SourceOver); p.setBrush(QBrush(bg)); p.drawRect(r); @@ -172,6 +183,8 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { QLinearGradient g(0, r.y(), 0, r.bottom()); g.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.05)); g.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0.35)); + + p.setCompositionMode(QPainter::CompositionMode_DestinationOver); p.setBrush(QBrush(g)); p.fillRect(r, g); p.setCompositionMode(QPainter::CompositionMode_SourceOver); @@ -212,10 +225,10 @@ NvgWindow::~NvgWindow() { void NvgWindow::initializeGL() { initializeOpenGLFunctions(); - std::cout << "OpenGL version: " << glGetString(GL_VERSION) << std::endl; - std::cout << "OpenGL vendor: " << glGetString(GL_VENDOR) << std::endl; - std::cout << "OpenGL renderer: " << glGetString(GL_RENDERER) << std::endl; - std::cout << "OpenGL language version: " << glGetString(GL_SHADING_LANGUAGE_VERSION) << std::endl; + qInfo() << "OpenGL version:" << QString((const char*)glGetString(GL_VERSION)); + qInfo() << "OpenGL vendor:" << QString((const char*)glGetString(GL_VENDOR)); + qInfo() << "OpenGL renderer:" << QString((const char*)glGetString(GL_RENDERER)); + qInfo() << "OpenGL language version:" << QString((const char*)glGetString(GL_SHADING_LANGUAGE_VERSION)); ui_nvg_init(&QUIState::ui_state); prev_draw_t = millis_since_boot(); @@ -223,7 +236,7 @@ void NvgWindow::initializeGL() { void NvgWindow::update(const UIState &s) { // Connecting to visionIPC requires opengl to be current - if (s.vipc_client->connected){ + if (s.vipc_client->connected) { makeCurrent(); } repaint(); diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index c3baf0103..ae2cfda8f 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -2,13 +2,16 @@ #include +#include +#include #include -#include +#include +#include #include "cereal/gen/cpp/log.capnp.h" #include "selfdrive/hardware/hw.h" -#include "selfdrive/ui/ui.h" #include "selfdrive/ui/qt/qt_window.h" +#include "selfdrive/ui/ui.h" typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; @@ -29,21 +32,9 @@ private: void updateAlert(const QString &t1, const QString &t2, float blink_rate, const std::string &type, cereal::ControlsState::AlertSize size, AudibleAlert sound); - std::map> sound_map { - // AudibleAlert, (file path, inf loop) - {AudibleAlert::CHIME_DISENGAGE, {"../assets/sounds/disengaged.wav", false}}, - {AudibleAlert::CHIME_ENGAGE, {"../assets/sounds/engaged.wav", false}}, - {AudibleAlert::CHIME_WARNING1, {"../assets/sounds/warning_1.wav", false}}, - {AudibleAlert::CHIME_WARNING2, {"../assets/sounds/warning_2.wav", false}}, - {AudibleAlert::CHIME_WARNING2_REPEAT, {"../assets/sounds/warning_2.wav", true}}, - {AudibleAlert::CHIME_WARNING_REPEAT, {"../assets/sounds/warning_repeat.wav", true}}, - {AudibleAlert::CHIME_ERROR, {"../assets/sounds/error.wav", false}}, - {AudibleAlert::CHIME_PROMPT, {"../assets/sounds/error.wav", false}} - }; - QColor bg; float volume = Hardware::MIN_VOLUME; - std::map sounds; + std::map> sounds; float blinking_rate = 0; QString text1, text2; std::string alert_type; @@ -86,7 +77,7 @@ public: private: OnroadAlerts *alerts; NvgWindow *nvg; - QStackedLayout *layout; + QStackedLayout *main_layout; QHBoxLayout* split; signals: diff --git a/selfdrive/ui/qt/qt_window.h b/selfdrive/ui/qt/qt_window.h index 295ab083f..307de6b29 100644 --- a/selfdrive/ui/qt/qt_window.h +++ b/selfdrive/ui/qt/qt_window.h @@ -13,7 +13,7 @@ #include "selfdrive/hardware/hw.h" -const int vwp_w = Hardware::TICI() ? 2160 : 1920; +const int vwp_w = (Hardware::TICI() || (getenv("WIDE_UI") != NULL)) ? 2160 : 1920; const int vwp_h = 1080; inline void setMainWindow(QWidget *w) { diff --git a/selfdrive/ui/qt/request_repeater.cc b/selfdrive/ui/qt/request_repeater.cc index ee6680cc7..7c11c0f8a 100644 --- a/selfdrive/ui/qt/request_repeater.cc +++ b/selfdrive/ui/qt/request_repeater.cc @@ -1,13 +1,33 @@ -#include "request_repeater.h" +#include "selfdrive/ui/qt/request_repeater.h" RequestRepeater::RequestRepeater(QObject *parent, const QString &requestURL, const QString &cacheKey, - int period) : HttpRequest(parent, requestURL, cacheKey) { + int period, bool while_onroad) : HttpRequest(parent, requestURL) { timer = new QTimer(this); timer->setTimerType(Qt::VeryCoarseTimer); - QObject::connect(timer, &QTimer::timeout, [=](){ - if (!QUIState::ui_state.scene.started && QUIState::ui_state.awake && reply == NULL) { + QObject::connect(timer, &QTimer::timeout, [=]() { + if ((!QUIState::ui_state.scene.started || while_onroad) && QUIState::ui_state.awake && reply == NULL) { sendRequest(requestURL); } }); + timer->start(period * 1000); + + if (!cacheKey.isEmpty()) { + prevResp = QString::fromStdString(params.get(cacheKey.toStdString())); + if (!prevResp.isEmpty()) { + QTimer::singleShot(0, [=]() { emit receivedResponse(prevResp); }); + } + QObject::connect(this, &HttpRequest::receivedResponse, [=](const QString &resp) { + if (resp != prevResp) { + params.put(cacheKey.toStdString(), resp.toStdString()); + prevResp = resp; + } + }); + QObject::connect(this, &HttpRequest::failedResponse, [=](const QString &err) { + if (!prevResp.isEmpty()) { + params.remove(cacheKey.toStdString()); + prevResp = ""; + } + }); + } } diff --git a/selfdrive/ui/qt/request_repeater.h b/selfdrive/ui/qt/request_repeater.h index c23bbbcf1..fa80100d2 100644 --- a/selfdrive/ui/qt/request_repeater.h +++ b/selfdrive/ui/qt/request_repeater.h @@ -1,12 +1,15 @@ #pragma once +#include "selfdrive/common/util.h" #include "selfdrive/ui/qt/api.h" #include "selfdrive/ui/ui.h" class RequestRepeater : public HttpRequest { public: - RequestRepeater(QObject *parent, const QString &requestURL, const QString &cacheKey = "", int period = 0); + RequestRepeater(QObject *parent, const QString &requestURL, const QString &cacheKey = "", int period = 0, bool while_onroad=false); private: + Params params; QTimer *timer; + QString prevResp; }; diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 198d99be1..ee315c142 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -1,5 +1,7 @@ #include "selfdrive/ui/qt/sidebar.h" +#include + #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" @@ -23,7 +25,7 @@ void Sidebar::drawMetric(QPainter &p, const QString &label, const QString &val, p.setPen(QColor(0xff, 0xff, 0xff)); if (val.isEmpty()) { configFont(p, "Open Sans", 35, "Bold"); - const QRect r = QRect(rect.x() + 35, rect.y(), rect.width() - 50, rect.height()); + const QRect r = QRect(rect.x() + 30, rect.y(), rect.width() - 40, rect.height()); p.drawText(r, Qt::AlignCenter, label); } else { configFont(p, "Open Sans", 58, "Bold"); @@ -35,7 +37,7 @@ void Sidebar::drawMetric(QPainter &p, const QString &label, const QString &val, Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { home_img = QImage("../assets/images/button_home.png").scaled(180, 180, Qt::KeepAspectRatio, Qt::SmoothTransformation); - settings_img = QImage("../assets/images/button_settings.png").scaled(settings_btn.width(), settings_btn.height(), Qt::IgnoreAspectRatio, Qt::SmoothTransformation);; + settings_img = QImage("../assets/images/button_settings.png").scaled(settings_btn.width(), settings_btn.height(), Qt::IgnoreAspectRatio, Qt::SmoothTransformation); connect(this, &Sidebar::valueChanged, [=] { update(); }); @@ -55,7 +57,8 @@ void Sidebar::updateState(const UIState &s) { auto deviceState = sm["deviceState"].getDeviceState(); setProperty("netType", network_type[deviceState.getNetworkType()]); - setProperty("netStrength", signal_imgs[deviceState.getNetworkStrength()]); + int strength = (int)deviceState.getNetworkStrength(); + setProperty("netStrength", strength > 0 ? strength + 1 : 0); auto last_ping = deviceState.getLastAthenaPingTime(); if (last_ping == 0) { @@ -82,9 +85,9 @@ void Sidebar::updateState(const UIState &s) { if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { pandaStatus = danger_color; pandaStr = "NO\nPANDA"; - } else if (Hardware::TICI() && s.scene.started) { - pandaStr = QString("SATS %1\nACC %2").arg(s.scene.satelliteCount).arg(fmin(10, s.scene.gpsAccuracy), 0, 'f', 2); - pandaStatus = sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK() ? good_color : warning_color; + } else if (s.scene.started && !sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK()) { + pandaStatus = warning_color; + pandaStr = "GPS\nSEARCHING"; } setProperty("pandaStr", pandaStr); setProperty("pandaStatus", pandaStatus); @@ -102,7 +105,14 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.drawImage(60, 1080 - 180 - 40, home_img); // network - p.drawImage(58, 196, net_strength); + int x = 58; + const QColor gray(0x54, 0x54, 0x54); + for (int i = 0; i < 5; ++i) { + p.setBrush(i < net_strength ? Qt::white : gray); + p.drawEllipse(x, 196, 27, 27); + x += 37; + } + configFont(p, "Open Sans", 35, "Regular"); p.setPen(QColor(0xff, 0xff, 0xff)); const QRect r = QRect(50, 247, 100, 50); diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index f03871045..9c955bb2b 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -1,6 +1,7 @@ #pragma once -#include +#include +#include #include "selfdrive/ui/ui.h" @@ -13,7 +14,7 @@ class Sidebar : public QFrame { Q_PROPERTY(int tempVal MEMBER temp_val NOTIFY valueChanged); Q_PROPERTY(QColor tempStatus MEMBER temp_status NOTIFY valueChanged); Q_PROPERTY(QString netType MEMBER net_type NOTIFY valueChanged); - Q_PROPERTY(QImage netStrength MEMBER net_strength NOTIFY valueChanged); + Q_PROPERTY(int netStrength MEMBER net_strength NOTIFY valueChanged); public: explicit Sidebar(QWidget* parent = 0); @@ -36,18 +37,12 @@ private: const QMap network_type = { {cereal::DeviceState::NetworkType::NONE, "--"}, {cereal::DeviceState::NetworkType::WIFI, "WiFi"}, + {cereal::DeviceState::NetworkType::ETHERNET, "ETH"}, {cereal::DeviceState::NetworkType::CELL2_G, "2G"}, {cereal::DeviceState::NetworkType::CELL3_G, "3G"}, {cereal::DeviceState::NetworkType::CELL4_G, "LTE"}, {cereal::DeviceState::NetworkType::CELL5_G, "5G"} }; - const QMap signal_imgs = { - {cereal::DeviceState::NetworkStrength::UNKNOWN, QImage("../assets/images/network_0.png")}, - {cereal::DeviceState::NetworkStrength::POOR, QImage("../assets/images/network_1.png")}, - {cereal::DeviceState::NetworkStrength::MODERATE, QImage("../assets/images/network_2.png")}, - {cereal::DeviceState::NetworkStrength::GOOD, QImage("../assets/images/network_3.png")}, - {cereal::DeviceState::NetworkStrength::GREAT, QImage("../assets/images/network_4.png")}, - }; const QRect settings_btn = QRect(50, 35, 200, 117); const QColor good_color = QColor(255, 255, 255); @@ -61,5 +56,5 @@ private: int temp_val = 0; QColor temp_status = warning_color; QString net_type; - QImage net_strength; + int net_strength = 0; }; diff --git a/selfdrive/ui/qt/spinner.cc b/selfdrive/ui/qt/spinner.cc index b91bd7bc4..0dcae6d97 100644 --- a/selfdrive/ui/qt/spinner.cc +++ b/selfdrive/ui/qt/spinner.cc @@ -1,6 +1,6 @@ -#include "spinner.h" +#include "selfdrive/ui/qt/spinner.h" -#include +#include #include #include @@ -12,18 +12,23 @@ #include "selfdrive/hardware/hw.h" #include "selfdrive/ui/qt/qt_window.h" +#include "selfdrive/ui/qt/util.h" TrackWidget::TrackWidget(QWidget *parent) : QWidget(parent) { setFixedSize(spinner_size); - setAutoFillBackground(false); - - comma_img = QPixmap("../assets/img_spinner_comma.png").scaled(spinner_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); + setAutoFillBackground(true); + setPalette(Qt::black); // pre-compute all the track imgs. make this a gif instead? - QTransform transform; + QPixmap comma_img = QPixmap("../assets/img_spinner_comma.png").scaled(spinner_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); + QTransform transform(1, 0, 0, 1, width() / 2, height() / 2); QPixmap track_img = QPixmap("../assets/img_spinner_track.png").scaled(spinner_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); - for (auto &img : track_imgs) { - img = track_img.transformed(transform.rotate(360/spinner_fps), Qt::SmoothTransformation); + for (QPixmap &img : track_imgs) { + img = comma_img; + QPainter p(&img); + p.setRenderHint(QPainter::SmoothPixmapTransform); + p.setTransform(transform.rotate(360 / spinner_fps)); + p.drawPixmap(-width() / 2, -height() / 2, track_img); } m_anim.setDuration(1000); @@ -36,24 +41,13 @@ TrackWidget::TrackWidget(QWidget *parent) : QWidget(parent) { void TrackWidget::paintEvent(QPaintEvent *event) { QPainter painter(this); - QRect bg(0, 0, painter.device()->width(), painter.device()->height()); - QBrush bgBrush("#000000"); - painter.fillRect(bg, bgBrush); - - int track_idx = m_anim.currentValue().toInt(); - QRect rect(track_imgs[track_idx].rect()); - rect.moveCenter(bg.center()); - painter.drawPixmap(rect.topLeft(), track_imgs[track_idx]); - - rect = comma_img.rect(); - rect.moveCenter(bg.center()); - painter.drawPixmap(rect.topLeft(), comma_img); + painter.drawPixmap(0, 0, track_imgs[m_anim.currentValue().toInt()]); } // Spinner -Spinner::Spinner(QWidget *parent) { - QGridLayout *main_layout = new QGridLayout(); +Spinner::Spinner(QWidget *parent) : QWidget(parent) { + QGridLayout *main_layout = new QGridLayout(this); main_layout->setSpacing(0); main_layout->setMargin(200); @@ -70,17 +64,14 @@ Spinner::Spinner(QWidget *parent) { progress_bar->setFixedHeight(20); main_layout->addWidget(progress_bar, 1, 0, Qt::AlignHCenter); - setLayout(main_layout); setStyleSheet(R"( Spinner { background-color: black; } - * { - background-color: transparent; - } QLabel { color: white; font-size: 80px; + background-color: transparent; } QProgressBar { background-color: #373737; @@ -114,19 +105,7 @@ void Spinner::update(int n) { } int main(int argc, char *argv[]) { - QSurfaceFormat fmt; -#ifdef __APPLE__ - fmt.setVersion(3, 2); - fmt.setProfile(QSurfaceFormat::OpenGLContextProfile::CoreProfile); - fmt.setRenderableType(QSurfaceFormat::OpenGL); -#else - fmt.setRenderableType(QSurfaceFormat::OpenGLES); -#endif - QSurfaceFormat::setDefaultFormat(fmt); - - Hardware::set_display_power(true); - Hardware::set_brightness(65); - + initApp(); QApplication a(argc, argv); Spinner spinner; setMainWindow(&spinner); diff --git a/selfdrive/ui/qt/spinner.h b/selfdrive/ui/qt/spinner.h index c54aea103..43d90a75b 100644 --- a/selfdrive/ui/qt/spinner.h +++ b/selfdrive/ui/qt/spinner.h @@ -1,7 +1,6 @@ #include #include -#include #include #include #include @@ -19,7 +18,6 @@ public: private: void paintEvent(QPaintEvent *event) override; std::array track_imgs; - QPixmap comma_img; QVariantAnimation m_anim; }; diff --git a/selfdrive/ui/qt/text.cc b/selfdrive/ui/qt/text.cc index 0708b30db..2d4ff8826 100644 --- a/selfdrive/ui/qt/text.cc +++ b/selfdrive/ui/qt/text.cc @@ -6,29 +6,28 @@ #include #include "selfdrive/hardware/hw.h" +#include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/widgets/scrollview.h" int main(int argc, char *argv[]) { + initApp(); QApplication a(argc, argv); QWidget window; setMainWindow(&window); - Hardware::set_display_power(true); - Hardware::set_brightness(65); - - QGridLayout *layout = new QGridLayout; - layout->setMargin(50); + QGridLayout *main_layout = new QGridLayout(&window); + main_layout->setMargin(50); QLabel *label = new QLabel(argv[1]); label->setWordWrap(true); label->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); ScrollView *scroll = new ScrollView(label); scroll->setVerticalScrollBarPolicy(Qt::ScrollBarAsNeeded); - layout->addWidget(scroll, 0, 0, Qt::AlignTop); + main_layout->addWidget(scroll, 0, 0, Qt::AlignTop); // Scroll to the bottom - QObject::connect(scroll->verticalScrollBar(), &QAbstractSlider::rangeChanged, [=](){ + QObject::connect(scroll->verticalScrollBar(), &QAbstractSlider::rangeChanged, [=]() { scroll->verticalScrollBar()->setValue(scroll->verticalScrollBar()->maximum()); }); @@ -42,9 +41,8 @@ int main(int argc, char *argv[]) { btn->setText("Exit"); QObject::connect(btn, &QPushButton::released, &a, &QApplication::quit); #endif - layout->addWidget(btn, 0, 0, Qt::AlignRight | Qt::AlignBottom); + main_layout->addWidget(btn, 0, 0, Qt::AlignRight | Qt::AlignBottom); - window.setLayout(layout); window.setStyleSheet(R"( * { outline: none; diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc new file mode 100644 index 000000000..1091624ac --- /dev/null +++ b/selfdrive/ui/qt/util.cc @@ -0,0 +1,112 @@ +#include "selfdrive/ui/qt/util.h" + +#include +#include +#include + +#include "selfdrive/common/params.h" +#include "selfdrive/common/swaglog.h" +#include "selfdrive/hardware/hw.h" + +QString getBrand() { + return Params().getBool("Passive") ? "dashcam" : "openpilot"; +} + +QString getBrandVersion() { + return getBrand() + " v" + QString::fromStdString(Params().get("Version")).left(14).trimmed(); +} + +void configFont(QPainter &p, const QString &family, int size, const QString &style) { + QFont f(family); + f.setPixelSize(size); + f.setStyleName(style); + p.setFont(f); +} + +void clearLayout(QLayout* layout) { + while (QLayoutItem* item = layout->takeAt(0)) { + if (QWidget* widget = item->widget()) { + widget->deleteLater(); + } + if (QLayout* childLayout = item->layout()) { + clearLayout(childLayout); + } + delete item; + } +} + +QString timeAgo(const QDateTime &date) { + int diff = date.secsTo(QDateTime::currentDateTimeUtc()); + + QString s; + if (diff < 60) { + s = "now"; + } else if (diff < 60 * 60) { + int minutes = diff / 60; + s = QString("%1 minute%2 ago").arg(minutes).arg(minutes > 1 ? "s" : ""); + } else if (diff < 60 * 60 * 24) { + int hours = diff / (60 * 60); + s = QString("%1 hour%2 ago").arg(hours).arg(hours > 1 ? "s" : ""); + } else if (diff < 3600 * 24 * 7) { + int days = diff / (60 * 60 * 24); + s = QString("%1 day%2 ago").arg(days).arg(days > 1 ? "s" : ""); + } else { + s = date.date().toString(); + } + + return s; +} + +void setQtSurfaceFormat() { + QSurfaceFormat fmt; +#ifdef __APPLE__ + fmt.setVersion(3, 2); + fmt.setProfile(QSurfaceFormat::OpenGLContextProfile::CoreProfile); + fmt.setRenderableType(QSurfaceFormat::OpenGL); +#else + fmt.setRenderableType(QSurfaceFormat::OpenGLES); +#endif + QSurfaceFormat::setDefaultFormat(fmt); +} + +void initApp() { + Hardware::set_display_power(true); + Hardware::set_brightness(65); + setQtSurfaceFormat(); + if (Hardware::EON()) { + QApplication::setAttribute(Qt::AA_ShareOpenGLContexts); + } +} + +ClickableWidget::ClickableWidget(QWidget *parent) : QWidget(parent) { } + +void ClickableWidget::mouseReleaseEvent(QMouseEvent *event) { + emit clicked(); +} + +// Fix stylesheets +void ClickableWidget::paintEvent(QPaintEvent *) { + QStyleOption opt; + opt.init(this); + QPainter p(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &p, this); +} + + +void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) { + static std::map levels = { + {QtMsgType::QtDebugMsg, 10}, + {QtMsgType::QtInfoMsg, 20}, + {QtMsgType::QtWarningMsg, 30}, + {QtMsgType::QtCriticalMsg, 40}, + {QtMsgType::QtSystemMsg, 40}, + {QtMsgType::QtFatalMsg, 50}, + }; + + std::string file, function; + if (context.file != nullptr) file = context.file; + if (context.function != nullptr) function = context.function; + + auto bts = msg.toUtf8(); + cloudlog_e(levels[type], file.c_str(), context.line, function.c_str(), "%s", bts.constData()); +} diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index c8c33504d..4928eae22 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -1,44 +1,42 @@ #pragma once -#include +#include +#include +#include +#include +#include +#include -inline void configFont(QPainter &p, QString family, int size, const QString &style) { - QFont f(family); - f.setPixelSize(size); - f.setStyleName(style); - p.setFont(f); -} +QString getBrand(); +QString getBrandVersion(); +void configFont(QPainter &p, const QString &family, int size, const QString &style); +void clearLayout(QLayout* layout); +void setQtSurfaceFormat(); +QString timeAgo(const QDateTime &date); +void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg); +void initApp(); -inline void clearLayout(QLayout* layout) { - while (QLayoutItem* item = layout->takeAt(0)) { - if (QWidget* widget = item->widget()) { - widget->deleteLater(); - } - if (QLayout* childLayout = item->layout()) { - clearLayout(childLayout); - } - delete item; - } -} -inline QString timeAgo(const QDateTime &date) { - int diff = date.secsTo(QDateTime::currentDateTimeUtc()); +// convenience class for wrapping layouts +class LayoutWidget : public QWidget { + Q_OBJECT - QString s; - if (diff < 60) { - s = "now"; - } else if (diff < 60 * 60) { - int minutes = diff / 60; - s = QString("%1 minute%2 ago").arg(minutes).arg(minutes > 1 ? "s" : ""); - } else if (diff < 60 * 60 * 24) { - int hours = diff / (60 * 60); - s = QString("%1 hour%2 ago").arg(hours).arg(hours > 1 ? "s" : ""); - } else if (diff < 3600 * 24 * 7) { - int days = diff / (60 * 60 * 24); - s = QString("%1 day%2 ago").arg(days).arg(days > 1 ? "s" : ""); - } else { - s = date.date().toString(); - } +public: + LayoutWidget(QLayout *l, QWidget *parent = nullptr) : QWidget(parent) { + setLayout(l); + }; +}; - return s; -} +class ClickableWidget : public QWidget { + Q_OBJECT + +public: + ClickableWidget(QWidget *parent = nullptr); + +protected: + void mouseReleaseEvent(QMouseEvent *event) override; + void paintEvent(QPaintEvent *) override; + +signals: + void clicked(); +}; diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index e8909c95b..f923225dd 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -84,10 +84,12 @@ CameraViewWidget::CameraViewWidget(VisionStreamType stream_type, QWidget* parent CameraViewWidget::~CameraViewWidget() { makeCurrent(); + if (isValid()) { + glDeleteVertexArrays(1, &frame_vao); + glDeleteBuffers(1, &frame_vbo); + glDeleteBuffers(1, &frame_ibo); + } doneCurrent(); - glDeleteVertexArrays(1, &frame_vao); - glDeleteBuffers(1, &frame_vbo); - glDeleteBuffers(1, &frame_ibo); } void CameraViewWidget::initializeGL() { @@ -127,12 +129,12 @@ void CameraViewWidget::initializeGL() { frame_mat = matmul(device_transform, get_driver_view_transform()); } else { auto intrinsic_matrix = stream_type == VISION_STREAM_RGB_WIDE ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; - float zoom_ = zoom / intrinsic_matrix.v[0]; + float zoom = ZOOM / intrinsic_matrix.v[0]; if (stream_type == VISION_STREAM_RGB_WIDE) { - zoom_ *= 0.5; + zoom *= 0.5; } - float zx = zoom_ * 2 * intrinsic_matrix.v[2] / width(); - float zy = zoom_ * 2 * intrinsic_matrix.v[5] / height(); + float zx = zoom * 2 * intrinsic_matrix.v[2] / width(); + float zy = zoom * 2 * intrinsic_matrix.v[5] / height(); const mat4 frame_transform = {{ zx, 0.0, 0.0, 0.0, diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index 24c586113..532f8e1d4 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -1,4 +1,7 @@ -#include "controls.h" +#include "selfdrive/ui/qt/widgets/controls.h" + +#include +#include QFrame *horizontal_line(QWidget *parent) { QFrame *line = new QFrame(parent); @@ -15,8 +18,8 @@ QFrame *horizontal_line(QWidget *parent) { } AbstractControl::AbstractControl(const QString &title, const QString &desc, const QString &icon, QWidget *parent) : QFrame(parent) { - QVBoxLayout *vlayout = new QVBoxLayout(); - vlayout->setMargin(0); + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setMargin(0); hlayout = new QHBoxLayout; hlayout->setMargin(0); @@ -36,7 +39,7 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons title_label->setStyleSheet("font-size: 50px; font-weight: 400; text-align: left;"); hlayout->addWidget(title_label); - vlayout->addLayout(hlayout); + main_layout->addLayout(hlayout); // description if (!desc.isEmpty()) { @@ -45,7 +48,7 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons description->setStyleSheet("font-size: 40px; color:grey"); description->setWordWrap(true); description->setVisible(false); - vlayout->addWidget(description); + main_layout->addWidget(description); connect(title_label, &QPushButton::clicked, [=]() { if (!description->isVisible()) { @@ -54,13 +57,60 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons description->setVisible(!description->isVisible()); }); } - - setLayout(vlayout); - setStyleSheet("background-color: transparent;"); } -void AbstractControl::hideEvent(QHideEvent *e){ - if(description != nullptr){ +void AbstractControl::hideEvent(QHideEvent *e) { + if(description != nullptr) { description->hide(); } } + +// controls + +ButtonControl::ButtonControl(const QString &title, const QString &text, const QString &desc, QWidget *parent) : AbstractControl(title, desc, "", parent) { + btn.setText(text); + btn.setStyleSheet(R"( + QPushButton { + padding: 0; + border-radius: 50px; + font-size: 35px; + font-weight: 500; + color: #E4E4E4; + background-color: #393939; + } + QPushButton:disabled { + color: #33E4E4E4; + } + )"); + btn.setFixedSize(250, 100); + QObject::connect(&btn, &QPushButton::released, this, &ButtonControl::released); + hlayout->addWidget(&btn); +} + +// ElidedLabel + +ElidedLabel::ElidedLabel(QWidget *parent) : ElidedLabel({}, parent) {} + +ElidedLabel::ElidedLabel(const QString &text, QWidget *parent) : QLabel(text.trimmed(), parent) { + setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); + setMinimumWidth(1); +} + +void ElidedLabel::resizeEvent(QResizeEvent* event) { + QLabel::resizeEvent(event); + lastText_ = elidedText_ = ""; +} + +void ElidedLabel::paintEvent(QPaintEvent *event) { + const QString curText = text(); + if (curText != lastText_) { + elidedText_ = fontMetrics().elidedText(curText, Qt::ElideRight, contentsRect().width()); + lastText_ = curText; + } + + QPainter painter(this); + drawFrame(&painter); + QStyleOption opt; + opt.initFrom(this); + style()->drawItemText(&painter, contentsRect(), alignment(), opt.palette, isEnabled(), elidedText_, foregroundRole()); +} diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index 238817ca3..2e8360f0c 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -4,13 +4,25 @@ #include #include #include -#include #include "selfdrive/common/params.h" #include "selfdrive/ui/qt/widgets/toggle.h" QFrame *horizontal_line(QWidget *parent = nullptr); +class ElidedLabel : public QLabel { + Q_OBJECT + + public: + explicit ElidedLabel(QWidget *parent = 0); + explicit ElidedLabel(const QString &text, QWidget *parent = 0); + + protected: + void paintEvent(QPaintEvent *event) override; + void resizeEvent(QResizeEvent* event) override; + QString lastText_, elidedText_; +}; + class AbstractControl : public QFrame { Q_OBJECT @@ -42,7 +54,7 @@ class LabelControl : public AbstractControl { Q_OBJECT public: - LabelControl(const QString &title, const QString &text, const QString &desc = "", QWidget *parent = nullptr) : AbstractControl(title, desc, "", parent) { + LabelControl(const QString &title, const QString &text = "", const QString &desc = "", QWidget *parent = nullptr) : AbstractControl(title, desc, "", parent) { label.setText(text); label.setAlignment(Qt::AlignRight | Qt::AlignVCenter); hlayout->addWidget(&label); @@ -50,7 +62,7 @@ public: void setText(const QString &text) { label.setText(text); } private: - QLabel label; + ElidedLabel label; }; // widget for a button with a label @@ -58,32 +70,15 @@ class ButtonControl : public AbstractControl { Q_OBJECT public: - template - ButtonControl(const QString &title, const QString &text, const QString &desc, Functor functor, const QString &icon = "", QWidget *parent = nullptr) : AbstractControl(title, desc, icon, parent) { - btn.setText(text); - btn.setStyleSheet(R"( - QPushButton { - padding: 0; - border-radius: 50px; - font-size: 35px; - font-weight: 500; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"); - btn.setFixedSize(250, 100); - QObject::connect(&btn, &QPushButton::released, functor); - hlayout->addWidget(&btn); - } - void setText(const QString &text) { btn.setText(text); } + ButtonControl(const QString &title, const QString &text, const QString &desc = "", QWidget *parent = nullptr); + inline void setText(const QString &text) { btn.setText(text); } + inline QString text() const { return btn.text(); } + +signals: + void released(); public slots: - void setEnabled(bool enabled) { - btn.setEnabled(enabled); - }; + void setEnabled(bool enabled) { btn.setEnabled(enabled); }; private: QPushButton btn; diff --git a/selfdrive/ui/qt/widgets/drive_stats.cc b/selfdrive/ui/qt/widgets/drive_stats.cc index 1395c150c..168633610 100644 --- a/selfdrive/ui/qt/widgets/drive_stats.cc +++ b/selfdrive/ui/qt/widgets/drive_stats.cc @@ -1,7 +1,7 @@ -#include "drive_stats.h" +#include "selfdrive/ui/qt/widgets/drive_stats.h" #include -#include +#include #include #include @@ -10,17 +10,65 @@ const double MILE_TO_KM = 1.60934; -static QLayout* build_stat_layout(QLabel** metric, const QString& name) { - QVBoxLayout* layout = new QVBoxLayout; - layout->setMargin(0); - *metric = new QLabel("0"); - (*metric)->setStyleSheet("font-size: 80px; font-weight: 600;"); - layout->addWidget(*metric, 0, Qt::AlignLeft); +namespace { +QLabel* numberLabel() { + QLabel* label = new QLabel("0"); + label->setStyleSheet("font-size: 80px; font-weight: 600;"); + return label; +} + +QLabel* unitLabel(const QString& name) { QLabel* label = new QLabel(name); label->setStyleSheet("font-size: 45px; font-weight: 500;"); - layout->addWidget(label, 0, Qt::AlignLeft); - return layout; + return label; +} + +} // namespace + +DriveStats::DriveStats(QWidget* parent) : QWidget(parent) { + metric_ = Params().getBool("IsMetric"); + + QGridLayout* main_layout = new QGridLayout(this); + main_layout->setMargin(0); + + auto add_stats_layouts = [=](const QString &title, StatsLabels& labels) { + int row = main_layout->rowCount(); + main_layout->addWidget(new QLabel(title), row++, 0, 1, 3); + + main_layout->addWidget(labels.routes = numberLabel(), row, 0, Qt::AlignLeft); + main_layout->addWidget(labels.distance = numberLabel(), row, 1, Qt::AlignLeft); + main_layout->addWidget(labels.hours = numberLabel(), row, 2, Qt::AlignLeft); + + main_layout->addWidget(unitLabel("DRIVES"), row + 1, 0, Qt::AlignLeft); + main_layout->addWidget(labels.distance_unit = unitLabel(getDistanceUnit()), row + 1, 1, Qt::AlignLeft); + main_layout->addWidget(unitLabel("HOURS"), row + 1, 2, Qt::AlignLeft); + }; + + add_stats_layouts("ALL TIME", all_); + add_stats_layouts("PAST WEEK", week_); + + std::string dongle_id = Params().get("DongleId"); + if (util::is_valid_dongle_id(dongle_id)) { + std::string url = "https://api.commadotai.com/v1.1/devices/" + dongle_id + "/stats"; + RequestRepeater* repeater = new RequestRepeater(this, QString::fromStdString(url), "ApiCache_DriveStats", 30); + QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &DriveStats::parseResponse); + } + + setStyleSheet(R"(QLabel {font-size: 48px; font-weight: 500;})"); +} + +void DriveStats::updateStats() { + auto update = [=](const QJsonObject& obj, StatsLabels& labels) { + labels.routes->setText(QString::number((int)obj["routes"].toDouble())); + labels.distance->setText(QString::number(int(obj["distance"].toDouble() * (metric_ ? MILE_TO_KM : 1)))); + labels.distance_unit->setText(getDistanceUnit()); + labels.hours->setText(QString::number((int)(obj["minutes"].toDouble() / 60))); + }; + + QJsonObject json = stats_.object(); + update(json["all"].toObject(), all_); + update(json["week"].toObject(), week_); } void DriveStats::parseResponse(const QString& response) { @@ -29,42 +77,14 @@ void DriveStats::parseResponse(const QString& response) { qDebug() << "JSON Parse failed on getting past drives statistics"; return; } - - auto update = [](const QJsonObject &obj, StatsLabels& labels, bool metric) { - labels.routes->setText(QString::number((int)obj["routes"].toDouble())); - labels.distance->setText(QString::number(int(obj["distance"].toDouble() * (metric ? MILE_TO_KM : 1)))); - labels.hours->setText(QString::number((int)(obj["minutes"].toDouble() / 60))); - }; - - QJsonObject json = doc.object(); - update(json["all"].toObject(), all_, metric); - update(json["week"].toObject(), week_, metric); + stats_ = doc; + updateStats(); } -DriveStats::DriveStats(QWidget* parent) : QWidget(parent) { - metric = Params().getBool("IsMetric"); - QString distance_unit = metric ? "KM" : "MILES"; - - auto add_stats_layouts = [&](QGridLayout* gl, StatsLabels& labels, int row, const QString &distance_unit) { - gl->addLayout(build_stat_layout(&labels.routes, "DRIVES"), row, 0, 3, 1); - gl->addLayout(build_stat_layout(&labels.distance, distance_unit), row, 1, 3, 1); - gl->addLayout(build_stat_layout(&labels.hours, "HOURS"), row, 2, 3, 1); - }; - - QGridLayout* gl = new QGridLayout(this); - gl->setMargin(0); - - gl->addWidget(new QLabel("ALL TIME"), 0, 0, 1, 3); - add_stats_layouts(gl, all_, 1, distance_unit); - - gl->addWidget(new QLabel("PAST WEEK"), 6, 0, 1, 3); - add_stats_layouts(gl, week_, 7, distance_unit); - - QString dongleId = QString::fromStdString(Params().get("DongleId")); - QString url = "https://api.commadotai.com/v1.1/devices/" + dongleId + "/stats"; - RequestRepeater *repeater = new RequestRepeater(this, url, "ApiCache_DriveStats", 30); - QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &DriveStats::parseResponse); - - setLayout(gl); - setStyleSheet(R"(QLabel {font-size: 48px; font-weight: 500;})"); +void DriveStats::showEvent(QShowEvent* event) { + bool metric = Params().getBool("IsMetric"); + if (metric_ != metric) { + metric_ = metric; + updateStats(); + } } diff --git a/selfdrive/ui/qt/widgets/drive_stats.h b/selfdrive/ui/qt/widgets/drive_stats.h index deeb80f65..2747487ff 100644 --- a/selfdrive/ui/qt/widgets/drive_stats.h +++ b/selfdrive/ui/qt/widgets/drive_stats.h @@ -1,5 +1,6 @@ #pragma once +#include #include class DriveStats : public QWidget { @@ -9,9 +10,14 @@ public: explicit DriveStats(QWidget* parent = 0); private: - bool metric; + void showEvent(QShowEvent *event) override; + void updateStats(); + inline QString getDistanceUnit() const { return metric_ ? "KM" : "MILES"; } + + bool metric_; + QJsonDocument stats_; struct StatsLabels { - QLabel *routes, *distance, *hours; + QLabel *routes, *distance, *distance_unit, *hours; } all_, week_; private slots: diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index 4e9d2e668..f3ef138ea 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -1,14 +1,26 @@ -#include "input.h" +#include "selfdrive/ui/qt/widgets/input.h" #include #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/hardware/hw.h" -InputDialog::InputDialog(const QString &prompt_text, QWidget *parent) : QDialog(parent) { - layout = new QVBoxLayout(); - layout->setContentsMargins(50, 50, 50, 50); - layout->setSpacing(20); +QDialogBase::QDialogBase(QWidget *parent) : QDialog(parent) { + Q_ASSERT(parent != nullptr); + parent->installEventFilter(this); +} + +bool QDialogBase::eventFilter(QObject *o, QEvent *e) { + if (o == parent() && e->type() == QEvent::Hide) { + reject(); + } + return QDialog::eventFilter(o, e); +} + +InputDialog::InputDialog(const QString &prompt_text, QWidget *parent) : QDialogBase(parent) { + main_layout = new QVBoxLayout(this); + main_layout->setContentsMargins(50, 50, 50, 50); + main_layout->setSpacing(20); // build header QHBoxLayout *header_layout = new QHBoxLayout(); @@ -30,10 +42,10 @@ InputDialog::InputDialog(const QString &prompt_text, QWidget *parent) : QDialog( QObject::connect(cancel_btn, &QPushButton::released, this, &InputDialog::reject); QObject::connect(cancel_btn, &QPushButton::released, this, &InputDialog::cancel); - layout->addLayout(header_layout); + main_layout->addLayout(header_layout); // text box - layout->addSpacing(20); + main_layout->addSpacing(20); line = new QLineEdit(); line->setStyleSheet(R"( border: none; @@ -42,24 +54,26 @@ InputDialog::InputDialog(const QString &prompt_text, QWidget *parent) : QDialog( font-weight: 500; padding: 10px; )"); - layout->addWidget(line, 1, Qt::AlignTop); + main_layout->addWidget(line, 1, Qt::AlignTop); k = new Keyboard(this); QObject::connect(k, &Keyboard::emitButton, this, &InputDialog::handleInput); - layout->addWidget(k, 2, Qt::AlignBottom); + main_layout->addWidget(k, 2, Qt::AlignBottom); setStyleSheet(R"( * { + outline: none; color: white; + font-family: Inter; background-color: black; } )"); - setLayout(layout); } -QString InputDialog::getText(const QString &prompt, int minLength) { - InputDialog d = InputDialog(prompt); +QString InputDialog::getText(const QString &prompt, QWidget *parent, int minLength, const QString &defaultText) { + InputDialog d = InputDialog(prompt, parent); + d.line->setText(defaultText); d.setMinLength(minLength); const int ret = d.exec(); return ret ? d.text() : QString(); @@ -74,62 +88,53 @@ int InputDialog::exec() { return QDialog::exec(); } -void InputDialog::show(){ +void InputDialog::show() { setMainWindow(this); } void InputDialog::handleInput(const QString &s) { if (!QString::compare(s,"⌫")) { line->backspace(); - } - - if (!QString::compare(s,"⏎")) { - if (line->text().length() >= minLength){ + } else if (!QString::compare(s,"⏎")) { + if (line->text().length() >= minLength) { done(QDialog::Accepted); emitText(line->text()); } else { setMessage("Need at least "+QString::number(minLength)+" characters!", false); } + } else { + line->insert(s.left(1)); } - - QVector control_buttons {"⇧", "↑", "ABC", "⏎", "#+=", "⌫", "123"}; - for(QString c : control_buttons) { - if (!QString::compare(s, c)) { - return; - } - } - - line->insert(s.left(1)); } -void InputDialog::setMessage(const QString &message, bool clearInputField){ +void InputDialog::setMessage(const QString &message, bool clearInputField) { label->setText(message); - if (clearInputField){ + if (clearInputField) { line->setText(""); } } -void InputDialog::setMinLength(int length){ +void InputDialog::setMinLength(int length) { minLength = length; } ConfirmationDialog::ConfirmationDialog(const QString &prompt_text, const QString &confirm_text, const QString &cancel_text, - QWidget *parent):QDialog(parent) { + QWidget *parent) : QDialogBase(parent) { setWindowFlags(Qt::Popup); - layout = new QVBoxLayout(); - layout->setMargin(25); + main_layout = new QVBoxLayout(this); + main_layout->setMargin(25); prompt = new QLabel(prompt_text, this); prompt->setWordWrap(true); prompt->setAlignment(Qt::AlignHCenter); prompt->setStyleSheet(R"(font-size: 55px; font-weight: 400;)"); - layout->addWidget(prompt, 1, Qt::AlignTop | Qt::AlignHCenter); + main_layout->addWidget(prompt, 1, Qt::AlignTop | Qt::AlignHCenter); // cancel + confirm buttons QHBoxLayout *btn_layout = new QHBoxLayout(); btn_layout->setSpacing(20); btn_layout->addStretch(1); - layout->addLayout(btn_layout); + main_layout->addLayout(btn_layout); if (cancel_text.length()) { QPushButton* cancel_btn = new QPushButton(cancel_text); @@ -158,8 +163,6 @@ ConfirmationDialog::ConfirmationDialog(const QString &prompt_text, const QString background-color: #44444400; } )"); - - setLayout(layout); } bool ConfirmationDialog::alert(const QString &prompt_text, QWidget *parent) { diff --git a/selfdrive/ui/qt/widgets/input.h b/selfdrive/ui/qt/widgets/input.h index 4ffd0a9bb..287727b9f 100644 --- a/selfdrive/ui/qt/widgets/input.h +++ b/selfdrive/ui/qt/widgets/input.h @@ -9,12 +9,20 @@ #include "selfdrive/ui/qt/widgets/keyboard.h" -class InputDialog : public QDialog { +class QDialogBase : public QDialog { + Q_OBJECT + +protected: + QDialogBase(QWidget *parent); + bool eventFilter(QObject *o, QEvent *e) override; +}; + +class InputDialog : public QDialogBase { Q_OBJECT public: - explicit InputDialog(const QString &prompt_text, QWidget* parent = 0); - static QString getText(const QString &prompt, int minLength = -1); + explicit InputDialog(const QString &prompt_text, QWidget *parent); + static QString getText(const QString &prompt, QWidget *parent, int minLength = -1, const QString &defaultText = ""); QString text(); void setMessage(const QString &message, bool clearInputField = true); void setMinLength(int length); @@ -25,7 +33,7 @@ private: QLineEdit *line; Keyboard *k; QLabel *label; - QVBoxLayout *layout; + QVBoxLayout *main_layout; public slots: int exec() override; @@ -38,18 +46,18 @@ signals: void emitText(const QString &text); }; -class ConfirmationDialog : public QDialog { +class ConfirmationDialog : public QDialogBase { Q_OBJECT public: - explicit ConfirmationDialog(const QString &prompt_text, const QString &confirm_text = "Ok", - const QString &cancel_text = "Cancel", QWidget* parent = 0); - static bool alert(const QString &prompt_text, QWidget *parent = 0); - static bool confirm(const QString &prompt_text, QWidget *parent = 0); + explicit ConfirmationDialog(const QString &prompt_text, const QString &confirm_text, + const QString &cancel_text, QWidget* parent); + static bool alert(const QString &prompt_text, QWidget *parent); + static bool confirm(const QString &prompt_text, QWidget *parent); private: QLabel *prompt; - QVBoxLayout *layout; + QVBoxLayout *main_layout; public slots: int exec() override; diff --git a/selfdrive/ui/qt/widgets/keyboard.cc b/selfdrive/ui/qt/widgets/keyboard.cc index 6613897b1..9ea8d1abb 100644 --- a/selfdrive/ui/qt/widgets/keyboard.cc +++ b/selfdrive/ui/qt/widgets/keyboard.cc @@ -1,74 +1,78 @@ -#include "keyboard.h" +#include "selfdrive/ui/qt/widgets/keyboard.h" #include -#include #include #include -#include #include const int DEFAULT_STRETCH = 1; const int SPACEBAR_STRETCH = 3; +const QString BACKSPACE_KEY = "⌫"; +const QString ENTER_KEY = "⏎"; + +const QStringList CONTROL_BUTTONS = {"↑", "↓", "ABC", "#+=", "123"}; + KeyboardLayout::KeyboardLayout(QWidget* parent, const std::vector>& layout) : QWidget(parent) { - QVBoxLayout* vlayout = new QVBoxLayout; - vlayout->setMargin(0); - vlayout->setSpacing(35); + QVBoxLayout* main_layout = new QVBoxLayout(this); + main_layout->setMargin(0); + main_layout->setSpacing(20); QButtonGroup* btn_group = new QButtonGroup(this); QObject::connect(btn_group, SIGNAL(buttonClicked(QAbstractButton*)), parent, SLOT(handleButton(QAbstractButton*))); for (const auto &s : layout) { QHBoxLayout *hlayout = new QHBoxLayout; - hlayout->setSpacing(25); + hlayout->setSpacing(15); - if (vlayout->count() == 1) { + if (main_layout->count() == 1) { hlayout->addSpacing(90); } for (const QString &p : s) { QPushButton* btn = new QPushButton(p); + if (p == BACKSPACE_KEY) { + btn->setAutoRepeat(true); + } else if (p == ENTER_KEY) { + btn->setStyleSheet("background-color: #465BEA;"); + } btn->setFixedHeight(135); btn_group->addButton(btn); hlayout->addWidget(btn, p == QString(" ") ? SPACEBAR_STRETCH : DEFAULT_STRETCH); } - if (vlayout->count() == 1) { + if (main_layout->count() == 1) { hlayout->addSpacing(90); } - vlayout->addLayout(hlayout); + main_layout->addLayout(hlayout); } setStyleSheet(R"( - * { - outline: none; - } QPushButton { - font-size: 65px; + font-size: 75px; margin: 0px; padding: 0px; - border-radius: 30px; + border-radius: 10px; color: #dddddd; background-color: #444444; } QPushButton:pressed { - background-color: #000000; + background-color: #333333; } )"); - setLayout(vlayout); } Keyboard::Keyboard(QWidget *parent) : QFrame(parent) { - main_layout = new QStackedLayout; + main_layout = new QStackedLayout(this); main_layout->setMargin(0); // lowercase std::vector> lowercase = { {"q","w","e","r","t","y","u","i","o","p"}, {"a","s","d","f","g","h","j","k","l"}, - {"⇧","z","x","c","v","b","n","m","⌫"}, - {"123"," ","⏎"}, + {"↑","z","x","c","v","b","n","m",BACKSPACE_KEY}, + {"123"," ",".",ENTER_KEY}, }; main_layout->addWidget(new KeyboardLayout(this, lowercase)); @@ -76,8 +80,8 @@ Keyboard::Keyboard(QWidget *parent) : QFrame(parent) { std::vector> uppercase = { {"Q","W","E","R","T","Y","U","I","O","P"}, {"A","S","D","F","G","H","J","K","L"}, - {"↑","Z","X","C","V","B","N","M","⌫"}, - {"123"," ","⏎"}, + {"↓","Z","X","C","V","B","N","M",BACKSPACE_KEY}, + {"123"," ",".",ENTER_KEY}, }; main_layout->addWidget(new KeyboardLayout(this, uppercase)); @@ -85,8 +89,8 @@ Keyboard::Keyboard(QWidget *parent) : QFrame(parent) { std::vector> numbers = { {"1","2","3","4","5","6","7","8","9","0"}, {"-","/",":",";","(",")","$","&&","@","\""}, - {"#+=",".",",","?","!","`","⌫"}, - {"ABC"," ","⏎"}, + {"#+=",".",",","?","!","`",BACKSPACE_KEY}, + {"ABC"," ",".",ENTER_KEY}, }; main_layout->addWidget(new KeyboardLayout(this, numbers)); @@ -94,34 +98,37 @@ Keyboard::Keyboard(QWidget *parent) : QFrame(parent) { std::vector> specials = { {"[","]","{","}","#","%","^","*","+","="}, {"_","\\","|","~","<",">","€","£","¥","•"}, - {"123",".",",","?","!","`","⌫"}, - {"ABC"," ","⏎"}, + {"123",".",",","?","!","`",BACKSPACE_KEY}, + {"ABC"," ",".",ENTER_KEY}, }; main_layout->addWidget(new KeyboardLayout(this, specials)); - setLayout(main_layout); main_layout->setCurrentIndex(0); } -void Keyboard::handleButton(QAbstractButton* m_button) { - QString id = m_button->text(); - if (!QString::compare(m_button->text(), "↑") || !QString::compare(m_button->text(), "ABC")) { +void Keyboard::handleButton(QAbstractButton* btn) { + const QString key = btn->text(); + if (!QString::compare(key, "↓") || !QString::compare(key, "ABC")) { main_layout->setCurrentIndex(0); } - if (!QString::compare(m_button->text(), "⇧")) { + if (!QString::compare(key, "↑")) { main_layout->setCurrentIndex(1); } - if (!QString::compare(m_button->text(), "123")) { + if (!QString::compare(key, "123")) { main_layout->setCurrentIndex(2); } - if (!QString::compare(m_button->text(), "#+=")) { + if (!QString::compare(key, "#+=")) { main_layout->setCurrentIndex(3); } - if (!QString::compare(m_button->text(), "⏎")) { + if (!QString::compare(key, BACKSPACE_KEY)) { main_layout->setCurrentIndex(0); } - if ("A" <= id && id <= "Z") { + if ("A" <= key && key <= "Z") { main_layout->setCurrentIndex(0); } - emit emitButton(m_button->text()); + + // TODO: break up into separate signals + if (!CONTROL_BUTTONS.contains(key)) { + emit emitButton(key); + } } diff --git a/selfdrive/ui/qt/widgets/keyboard.h b/selfdrive/ui/qt/widgets/keyboard.h index c89f4fc6a..14df6c733 100644 --- a/selfdrive/ui/qt/widgets/keyboard.h +++ b/selfdrive/ui/qt/widgets/keyboard.h @@ -7,6 +7,7 @@ #include #include #include + class KeyboardLayout : public QWidget { Q_OBJECT diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.cc b/selfdrive/ui/qt/widgets/offroad_alerts.cc index 7816b251f..0fcdb8716 100644 --- a/selfdrive/ui/qt/widgets/offroad_alerts.cc +++ b/selfdrive/ui/qt/widgets/offroad_alerts.cc @@ -1,53 +1,39 @@ -#include "offroad_alerts.h" +#include "selfdrive/ui/qt/widgets/offroad_alerts.h" #include #include #include -#include +#include #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" +#include "selfdrive/ui/qt/widgets/scrollview.h" -OffroadAlert::OffroadAlert(QWidget* parent) : QFrame(parent) { - QVBoxLayout *layout = new QVBoxLayout; - layout->setMargin(50); - layout->setSpacing(30); +AbstractAlert::AbstractAlert(bool hasRebootBtn, QWidget *parent) : QFrame(parent) { + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setMargin(50); + main_layout->setSpacing(30); - QWidget *alerts_widget = new QWidget(this); - alerts_layout = new QVBoxLayout; - alerts_layout->setMargin(0); - alerts_layout->setSpacing(30); - alerts_widget->setLayout(alerts_layout); - alerts_widget->setStyleSheet("background-color: transparent;"); - - // release notes - releaseNotes.setWordWrap(true); - releaseNotes.setVisible(false); - releaseNotes.setStyleSheet("font-size: 48px;"); - releaseNotes.setAlignment(Qt::AlignTop); - - releaseNotesScroll = new ScrollView(&releaseNotes, this); - layout->addWidget(releaseNotesScroll); - - alertsScroll = new ScrollView(alerts_widget, this); - layout->addWidget(alertsScroll); + QWidget *widget = new QWidget; + scrollable_layout = new QVBoxLayout(widget); + widget->setStyleSheet("background-color: transparent;"); + main_layout->addWidget(new ScrollView(widget)); // bottom footer, dismiss + reboot buttons QHBoxLayout *footer_layout = new QHBoxLayout(); - layout->addLayout(footer_layout); + main_layout->addLayout(footer_layout); QPushButton *dismiss_btn = new QPushButton("Dismiss"); dismiss_btn->setFixedSize(400, 125); footer_layout->addWidget(dismiss_btn, 0, Qt::AlignBottom | Qt::AlignLeft); - QObject::connect(dismiss_btn, &QPushButton::released, this, &OffroadAlert::closeAlerts); + QObject::connect(dismiss_btn, &QPushButton::released, this, &AbstractAlert::dismiss); - rebootBtn.setText("Reboot and Update"); - rebootBtn.setFixedSize(600, 125); - rebootBtn.setVisible(false); - footer_layout->addWidget(&rebootBtn, 0, Qt::AlignBottom | Qt::AlignRight); - QObject::connect(&rebootBtn, &QPushButton::released, [=]() { Hardware::reboot(); }); - - setLayout(layout); + if (hasRebootBtn) { + QPushButton *rebootBtn = new QPushButton("Reboot and Update"); + rebootBtn->setFixedSize(600, 125); + footer_layout->addWidget(rebootBtn, 0, Qt::AlignBottom | Qt::AlignRight); + QObject::connect(rebootBtn, &QPushButton::released, [=]() { Hardware::reboot(); }); + } setStyleSheet(R"( * { font-size: 48px; @@ -66,49 +52,55 @@ OffroadAlert::OffroadAlert(QWidget* parent) : QFrame(parent) { )"); } -void OffroadAlert::refresh() { +int OffroadAlert::refresh() { if (alerts.empty()) { // setup labels for each alert - QString json = QString::fromStdString(util::read_file("../controls/lib/alerts_offroad.json")); + QString json = util::read_file("../controls/lib/alerts_offroad.json").c_str(); QJsonObject obj = QJsonDocument::fromJson(json.toUtf8()).object(); - for (auto &k : obj.keys()) { - QLabel *l = new QLabel(this); - alerts[k.toStdString()] = l; - int severity = obj[k].toObject()["severity"].toInt(); + // descending sort labels by severity + std::vector> sorted; + for (auto it = obj.constBegin(); it != obj.constEnd(); ++it) { + sorted.push_back({it.key().toStdString(), it.value()["severity"].toInt()}); + } + std::sort(sorted.begin(), sorted.end(), [=](auto &l, auto &r) { return l.second > r.second; }); + for (auto &[key, severity] : sorted) { + QLabel *l = new QLabel(this); + alerts[key] = l; l->setMargin(60); l->setWordWrap(true); - l->setStyleSheet("background-color: " + QString(severity ? "#E22C2C" : "#292929")); - l->setVisible(false); - alerts_layout->addWidget(l); + l->setStyleSheet(QString("background-color: %1").arg(severity ? "#E22C2C" : "#292929")); + scrollable_layout->addWidget(l); } - alerts_layout->addStretch(1); + scrollable_layout->addStretch(1); } - updateAlerts(); - - rebootBtn.setVisible(updateAvailable); - releaseNotesScroll->setVisible(updateAvailable); - releaseNotes.setText(QString::fromStdString(params.get("ReleaseNotes"))); - - alertsScroll->setVisible(!updateAvailable); - for (const auto& [k, label] : alerts) { - label->setVisible(!label->text().isEmpty()); - } -} - -void OffroadAlert::updateAlerts() { - alertCount = 0; - updateAvailable = params.getBool("UpdateAvailable"); - for (const auto& [key, label] : alerts) { - auto bytes = params.get(key.c_str()); + int alertCount = 0; + for (const auto &[key, label] : alerts) { + QString text; + std::string bytes = params.get(key); if (bytes.size()) { - QJsonDocument doc_par = QJsonDocument::fromJson(QByteArray(bytes.data(), bytes.size())); - QJsonObject obj = doc_par.object(); - label->setText(obj.value("text").toString()); - alertCount++; - } else { - label->setText(""); + auto doc_par = QJsonDocument::fromJson(bytes.c_str()); + text = doc_par["text"].toString(); } + label->setText(text); + label->setVisible(!text.isEmpty()); + alertCount += !text.isEmpty(); } + return alertCount; +} + +UpdateAlert::UpdateAlert(QWidget *parent) : AbstractAlert(true, parent) { + releaseNotes = new QLabel(this); + releaseNotes->setWordWrap(true); + releaseNotes->setAlignment(Qt::AlignTop); + scrollable_layout->addWidget(releaseNotes); +} + +bool UpdateAlert::refresh() { + bool updateAvailable = params.getBool("UpdateAvailable"); + if (updateAvailable) { + releaseNotes->setText(params.get("ReleaseNotes").c_str()); + } + return updateAvailable; } diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.h b/selfdrive/ui/qt/widgets/offroad_alerts.h index 88a69c8da..c285457c6 100644 --- a/selfdrive/ui/qt/widgets/offroad_alerts.h +++ b/selfdrive/ui/qt/widgets/offroad_alerts.h @@ -2,37 +2,41 @@ #include -#include #include -#include #include #include "selfdrive/common/params.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" -class OffroadAlert : public QFrame { +class AbstractAlert : public QFrame { + Q_OBJECT + +protected: + AbstractAlert(bool hasRebootBtn, QWidget *parent = nullptr); + QVBoxLayout *scrollable_layout; + Params params; + +signals: + void dismiss(); +}; + +class UpdateAlert : public AbstractAlert { Q_OBJECT public: - explicit OffroadAlert(QWidget *parent = 0); - int alertCount = 0; - bool updateAvailable; + UpdateAlert(QWidget *parent = 0); + bool refresh(); private: - void updateAlerts(); - - Params params; - std::map alerts; - - QLabel releaseNotes; - QPushButton rebootBtn; - ScrollView *alertsScroll; - ScrollView *releaseNotesScroll; - QVBoxLayout *alerts_layout; - -signals: - void closeAlerts(); - -public slots: - void refresh(); + QLabel *releaseNotes = nullptr; +}; + +class OffroadAlert : public AbstractAlert { + Q_OBJECT + +public: + explicit OffroadAlert(QWidget *parent = 0) : AbstractAlert(false, parent) {} + int refresh(); + +private: + std::map alerts; }; diff --git a/selfdrive/ui/qt/widgets/scrollview.cc b/selfdrive/ui/qt/widgets/scrollview.cc index 31be17c7b..18cd6ee67 100644 --- a/selfdrive/ui/qt/widgets/scrollview.cc +++ b/selfdrive/ui/qt/widgets/scrollview.cc @@ -1,8 +1,9 @@ -#include "scrollview.h" +#include "selfdrive/ui/qt/widgets/scrollview.h" #include +#include -ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent){ +ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent) { setWidget(w); setWidgetResizable(true); setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); @@ -42,6 +43,6 @@ ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent){ scroller->setScrollerProperties(sp); } -void ScrollView::hideEvent(QHideEvent *e){ +void ScrollView::hideEvent(QHideEvent *e) { verticalScrollBar()->setValue(0); } diff --git a/selfdrive/ui/qt/widgets/scrollview.h b/selfdrive/ui/qt/widgets/scrollview.h index 755ed646f..024331aa3 100644 --- a/selfdrive/ui/qt/widgets/scrollview.h +++ b/selfdrive/ui/qt/widgets/scrollview.h @@ -1,7 +1,6 @@ #pragma once #include -#include class ScrollView : public QScrollArea { Q_OBJECT diff --git a/selfdrive/ui/qt/widgets/setup.cc b/selfdrive/ui/qt/widgets/setup.cc index 2633220ea..f16e773a7 100644 --- a/selfdrive/ui/qt/widgets/setup.cc +++ b/selfdrive/ui/qt/widgets/setup.cc @@ -1,4 +1,4 @@ -#include "setup.h" +#include "selfdrive/ui/qt/widgets/setup.h" #include #include @@ -10,7 +10,6 @@ #include #include -#include "selfdrive/common/params.h" #include "selfdrive/ui/qt/request_repeater.h" using qrcodegen::QrCode; @@ -18,37 +17,25 @@ using qrcodegen::QrCode; PairingQRWidget::PairingQRWidget(QWidget* parent) : QWidget(parent) { qrCode = new QLabel; qrCode->setScaledContents(true); - QVBoxLayout* v = new QVBoxLayout; - v->addWidget(qrCode, 0, Qt::AlignCenter); - setLayout(v); + QVBoxLayout* main_layout = new QVBoxLayout(this); + main_layout->addWidget(qrCode, 0, Qt::AlignCenter); QTimer* timer = new QTimer(this); timer->start(30 * 1000); connect(timer, &QTimer::timeout, this, &PairingQRWidget::refresh); } -void PairingQRWidget::showEvent(QShowEvent *event){ +void PairingQRWidget::showEvent(QShowEvent *event) { refresh(); } -void PairingQRWidget::refresh(){ - Params params; - QString IMEI = QString::fromStdString(params.get("IMEI")); - QString serial = QString::fromStdString(params.get("HardwareSerial")); - - if (std::min(IMEI.length(), serial.length()) <= 5) { - qrCode->setText("Error getting serial: contact support"); - qrCode->setWordWrap(true); - qrCode->setStyleSheet(R"(font-size: 60px;)"); - return; - } +void PairingQRWidget::refresh() { QString pairToken = CommaApi::create_jwt({{"pair", true}}); - - QString qrString = IMEI + "--" + serial + "--" + pairToken; + QString qrString = "https://my.comma.ai/?pair=" + pairToken; this->updateQrCode(qrString); } -void PairingQRWidget::updateQrCode(QString text) { +void PairingQRWidget::updateQrCode(const QString &text) { QrCode qr = QrCode::encodeText(text.toUtf8().data(), QrCode::Ecc::LOW); qint32 sz = qr.getSize(); // make the image larger so we can have a white border @@ -73,7 +60,7 @@ void PairingQRWidget::updateQrCode(QString text) { } PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) { - mainLayout = new QVBoxLayout; + mainLayout = new QVBoxLayout(this); mainLayout->setMargin(30); QLabel* commaPrime = new QLabel("COMMA PRIME"); @@ -94,7 +81,6 @@ PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) { points = new QLabel(); mainLayout->addWidget(points, 0, Qt::AlignTop); - setLayout(mainLayout); setStyleSheet(R"( QLabel { font-size: 70px; @@ -103,14 +89,12 @@ PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) { )"); // set up API requests - QString dongleId = QString::fromStdString(Params().get("DongleId")); - if (!dongleId.length()) { - return; + std::string dongleId = Params().get("DongleId"); + if (util::is_valid_dongle_id(dongleId)) { + std::string url = "https://api.commadotai.com/v1/devices/" + dongleId + "/owner"; + RequestRepeater *repeater = new RequestRepeater(this, QString::fromStdString(url), "ApiCache_Owner", 6); + QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &PrimeUserWidget::replyFinished); } - - QString url = "https://api.commadotai.com/v1/devices/" + dongleId + "/owner"; - RequestRepeater *repeater = new RequestRepeater(this, url, "ApiCache_Owner", 6); - QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &PrimeUserWidget::replyFinished); } void PrimeUserWidget::replyFinished(const QString &response) { @@ -132,11 +116,11 @@ void PrimeUserWidget::replyFinished(const QString &response) { } PrimeAdWidget::PrimeAdWidget(QWidget* parent) : QWidget(parent) { - QVBoxLayout* vlayout = new QVBoxLayout; - vlayout->setMargin(30); - vlayout->setSpacing(15); + QVBoxLayout* main_layout = new QVBoxLayout(this); + main_layout->setMargin(30); + main_layout->setSpacing(15); - vlayout->addWidget(new QLabel("Upgrade now"), 1, Qt::AlignTop); + main_layout->addWidget(new QLabel("Upgrade now"), 1, Qt::AlignTop); QLabel* description = new QLabel("Become a comma prime member at my.comma.ai and get premium features!"); description->setStyleSheet(R"( @@ -144,16 +128,14 @@ PrimeAdWidget::PrimeAdWidget(QWidget* parent) : QWidget(parent) { color: #b8b8b8; )"); description->setWordWrap(true); - vlayout->addWidget(description, 2, Qt::AlignTop); + main_layout->addWidget(description, 2, Qt::AlignTop); QVector features = {"✓ REMOTE ACCESS", "✓ 14 DAYS OF STORAGE", "✓ DEVELOPER PERKS"}; for (auto &f: features) { QLabel* feature = new QLabel(f); feature->setStyleSheet(R"(font-size: 40px;)"); - vlayout->addWidget(feature, 0, Qt::AlignBottom); + main_layout->addWidget(feature, 0, Qt::AlignBottom); } - - setLayout(vlayout); } @@ -162,7 +144,8 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { // Unpaired, registration prompt layout - QVBoxLayout* finishRegistationLayout = new QVBoxLayout; + QWidget* finishRegistration = new QWidget; + QVBoxLayout* finishRegistationLayout = new QVBoxLayout(finishRegistration); finishRegistationLayout->setMargin(30); QLabel* registrationDescription = new QLabel("Pair your device with the comma connect app"); @@ -186,16 +169,15 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { finishRegistationLayout->addWidget(finishButton); QObject::connect(finishButton, &QPushButton::released, this, &SetupWidget::showQrCode); - QWidget* finishRegistration = new QWidget; - finishRegistration->setLayout(finishRegistationLayout); mainLayout->addWidget(finishRegistration); // Pairing QR code layout - QVBoxLayout* qrLayout = new QVBoxLayout; + QWidget* q = new QWidget; + QVBoxLayout* qrLayout = new QVBoxLayout(q); qrLayout->addSpacing(30); - QLabel* qrLabel = new QLabel("Scan with comma connect!"); + QLabel* qrLabel = new QLabel("Scan QR code to pair!"); qrLabel->setWordWrap(true); qrLabel->setAlignment(Qt::AlignHCenter); qrLabel->setStyleSheet(R"( @@ -206,8 +188,6 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { qrLayout->addWidget(new PairingQRWidget, 1); - QWidget* q = new QWidget; - q->setLayout(qrLayout); mainLayout->addWidget(q); primeAd = new PrimeAdWidget; @@ -218,9 +198,8 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { mainLayout->setCurrentWidget(primeAd); - QVBoxLayout *layout = new QVBoxLayout; - layout->addWidget(mainLayout); - setLayout(layout); + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->addWidget(mainLayout); setStyleSheet(R"( SetupWidget { @@ -239,12 +218,14 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { setSizePolicy(sp_retain); // set up API requests - QString dongleId = QString::fromStdString(Params().get("DongleId")); - QString url = "https://api.commadotai.com/v1.1/devices/" + dongleId + "/"; - RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_Device", 5); + std::string dongleId = Params().get("DongleId"); + if (util::is_valid_dongle_id(dongleId)) { + std::string url = "https://api.commadotai.com/v1.1/devices/" + dongleId + "/"; + RequestRepeater* repeater = new RequestRepeater(this, QString::fromStdString(url), "ApiCache_Device", 5); - QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &SetupWidget::replyFinished); - QObject::connect(repeater, &RequestRepeater::failedResponse, this, &SetupWidget::parseError); + QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &SetupWidget::replyFinished); + QObject::connect(repeater, &RequestRepeater::failedResponse, this, &SetupWidget::parseError); + } hide(); // Only show when first request comes back } @@ -254,7 +235,7 @@ void SetupWidget::parseError(const QString &response) { mainLayout->setCurrentIndex(0); } -void SetupWidget::showQrCode(){ +void SetupWidget::showQrCode() { showQr = true; mainLayout->setCurrentIndex(1); } diff --git a/selfdrive/ui/qt/widgets/setup.h b/selfdrive/ui/qt/widgets/setup.h index 169dd594f..02c47bd3e 100644 --- a/selfdrive/ui/qt/widgets/setup.h +++ b/selfdrive/ui/qt/widgets/setup.h @@ -5,8 +5,6 @@ #include #include -#include "selfdrive/ui/qt/api.h" - class PairingQRWidget : public QWidget { Q_OBJECT @@ -15,7 +13,7 @@ public: private: QLabel* qrCode; - void updateQrCode(QString text); + void updateQrCode(const QString &text); void showEvent(QShowEvent *event) override; private slots: @@ -31,7 +29,6 @@ private: QVBoxLayout* mainLayout; QLabel* username; QLabel* points; - CommaApi* api; private slots: void replyFinished(const QString &response); @@ -51,7 +48,6 @@ public: private: QStackedWidget* mainLayout; - CommaApi* api; PrimeAdWidget *primeAd; PrimeUserWidget *primeUser; bool showQr = false; diff --git a/selfdrive/ui/qt/widgets/ssh_keys.cc b/selfdrive/ui/qt/widgets/ssh_keys.cc index d180d558c..a9a03fbf1 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.cc +++ b/selfdrive/ui/qt/widgets/ssh_keys.cc @@ -1,38 +1,20 @@ -#include "ssh_keys.h" - -#include -#include +#include "selfdrive/ui/qt/widgets/ssh_keys.h" #include "selfdrive/common/params.h" #include "selfdrive/ui/qt/api.h" #include "selfdrive/ui/qt/widgets/input.h" -SshControl::SshControl() : AbstractControl("SSH Keys", "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.", "") { - - // setup widget - hlayout->addStretch(1); - - username_label.setAlignment(Qt::AlignVCenter); +SshControl::SshControl() : ButtonControl("SSH Keys", "", "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.") { + username_label.setAlignment(Qt::AlignRight | Qt::AlignVCenter); username_label.setStyleSheet("color: #aaaaaa"); - hlayout->addWidget(&username_label); + hlayout->insertWidget(1, &username_label); - btn.setStyleSheet(R"( - padding: 0; - border-radius: 50px; - font-size: 35px; - font-weight: 500; - color: #E4E4E4; - background-color: #393939; - )"); - btn.setFixedSize(250, 100); - hlayout->addWidget(&btn); - - QObject::connect(&btn, &QPushButton::released, [=]() { - if (btn.text() == "ADD") { - QString username = InputDialog::getText("Enter your GitHub username"); + QObject::connect(this, &ButtonControl::released, [=]() { + if (text() == "ADD") { + QString username = InputDialog::getText("Enter your GitHub username", this); if (username.length() > 0) { - btn.setText("LOADING"); - btn.setEnabled(false); + setText("LOADING"); + setEnabled(false); getUserKeys(username); } } else { @@ -49,34 +31,33 @@ void SshControl::refresh() { QString param = QString::fromStdString(params.get("GithubSshKeys")); if (param.length()) { username_label.setText(QString::fromStdString(params.get("GithubUsername"))); - btn.setText("REMOVE"); + setText("REMOVE"); } else { username_label.setText(""); - btn.setText("ADD"); + setText("ADD"); } - btn.setEnabled(true); + setEnabled(true); } void SshControl::getUserKeys(const QString &username) { - HttpRequest *request = new HttpRequest(this, "https://github.com/" + username + ".keys", "", false); + HttpRequest *request = new HttpRequest(this, "https://github.com/" + username + ".keys", false); QObject::connect(request, &HttpRequest::receivedResponse, [=](const QString &resp) { if (!resp.isEmpty()) { - Params params; params.put("GithubUsername", username.toStdString()); params.put("GithubSshKeys", resp.toStdString()); } else { - ConfirmationDialog::alert("Username '" + username + "' has no keys on GitHub"); + ConfirmationDialog::alert("Username '" + username + "' has no keys on GitHub", this); } refresh(); request->deleteLater(); }); QObject::connect(request, &HttpRequest::failedResponse, [=] { - ConfirmationDialog::alert("Username '" + username + "' doesn't exist on GitHub"); + ConfirmationDialog::alert("Username '" + username + "' doesn't exist on GitHub", this); refresh(); request->deleteLater(); }); QObject::connect(request, &HttpRequest::timeoutResponse, [=] { - ConfirmationDialog::alert("Request timed out"); + ConfirmationDialog::alert("Request timed out", this); refresh(); request->deleteLater(); }); diff --git a/selfdrive/ui/qt/widgets/ssh_keys.h b/selfdrive/ui/qt/widgets/ssh_keys.h index aaa7f80dc..0614e8c1d 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.h +++ b/selfdrive/ui/qt/widgets/ssh_keys.h @@ -18,7 +18,7 @@ public: }; // SSH key management widget -class SshControl : public AbstractControl { +class SshControl : public ButtonControl { Q_OBJECT public: @@ -27,7 +27,6 @@ public: private: Params params; - QPushButton btn; QLabel username_label; void refresh(); diff --git a/selfdrive/ui/qt/widgets/toggle.cc b/selfdrive/ui/qt/widgets/toggle.cc index d4eb215d3..e319f8017 100644 --- a/selfdrive/ui/qt/widgets/toggle.cc +++ b/selfdrive/ui/qt/widgets/toggle.cc @@ -1,4 +1,6 @@ -#include "toggle.h" +#include "selfdrive/ui/qt/widgets/toggle.h" + +#include Toggle::Toggle(QWidget *parent) : QAbstractButton(parent), _height(80), @@ -35,12 +37,12 @@ void Toggle::paintEvent(QPaintEvent *e) { } void Toggle::mouseReleaseEvent(QMouseEvent *e) { - if(!enabled){ + if(!enabled) { return; } const int left = _radius; const int right = width() - _radius; - if(_x_circle != left && _x_circle != right){ + if(_x_circle != left && _x_circle != right) { //Don't parse touch events, while the animation is running return; } @@ -65,13 +67,13 @@ void Toggle::enterEvent(QEvent *e) { QAbstractButton::enterEvent(e); } -bool Toggle::getEnabled(){ +bool Toggle::getEnabled() { return enabled; } -void Toggle::setEnabled(bool value){ +void Toggle::setEnabled(bool value) { enabled = value; - if(value){ + if(value) { circleColor.setRgb(0xfafafa); green.setRgb(0x33ab4c); }else{ diff --git a/selfdrive/ui/qt/widgets/toggle.h b/selfdrive/ui/qt/widgets/toggle.h index d2773f207..e7263a008 100644 --- a/selfdrive/ui/qt/widgets/toggle.h +++ b/selfdrive/ui/qt/widgets/toggle.h @@ -1,6 +1,8 @@ #pragma once -#include +#include +#include +#include class Toggle : public QAbstractButton { Q_OBJECT diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc index fe7539616..04c50684b 100644 --- a/selfdrive/ui/qt/window.cc +++ b/selfdrive/ui/qt/window.cc @@ -1,11 +1,19 @@ -#include "window.h" +#include "selfdrive/ui/qt/window.h" + +#include #include "selfdrive/hardware/hw.h" MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { - main_layout = new QStackedLayout; + main_layout = new QStackedLayout(this); main_layout->setMargin(0); + onboardingWindow = new OnboardingWindow(this); + main_layout->addWidget(onboardingWindow); + QObject::connect(onboardingWindow, &OnboardingWindow::onboardingDone, [=]() { + main_layout->setCurrentWidget(homeWindow); + }); + homeWindow = new HomeWindow(this); main_layout->addWidget(homeWindow); QObject::connect(homeWindow, &HomeWindow::openSettings, this, &MainWindow::openSettings); @@ -19,26 +27,25 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { main_layout->addWidget(settingsWindow); QObject::connect(settingsWindow, &SettingsWindow::closeSettings, this, &MainWindow::closeSettings); QObject::connect(&qs, &QUIState::offroadTransition, settingsWindow, &SettingsWindow::offroadTransition); - QObject::connect(settingsWindow, &SettingsWindow::reviewTrainingGuide, this, &MainWindow::reviewTrainingGuide); + QObject::connect(settingsWindow, &SettingsWindow::reviewTrainingGuide, [=]() { + main_layout->setCurrentWidget(onboardingWindow); + }); QObject::connect(settingsWindow, &SettingsWindow::showDriverView, [=] { homeWindow->showDriverView(true); }); - onboardingWindow = new OnboardingWindow(this); - onboardingDone = onboardingWindow->isOnboardingDone(); - main_layout->addWidget(onboardingWindow); - - main_layout->setCurrentWidget(onboardingWindow); - QObject::connect(onboardingWindow, &OnboardingWindow::onboardingDone, [=](){ - onboardingDone = true; - closeSettings(); - }); - onboardingWindow->updateActiveScreen(); - device.setAwake(true, true); QObject::connect(&qs, &QUIState::uiUpdate, &device, &Device::update); - QObject::connect(&qs, &QUIState::offroadTransition, this, &MainWindow::offroadTransition); - QObject::connect(&device, &Device::displayPowerChanged, this, &MainWindow::closeSettings); + QObject::connect(&qs, &QUIState::offroadTransition, [=](bool offroad) { + if (!offroad) { + closeSettings(); + } + }); + QObject::connect(&device, &Device::displayPowerChanged, [=]() { + if(main_layout->currentWidget() != onboardingWindow) { + closeSettings(); + } + }); // load fonts QFontDatabase::addApplicationFont("../assets/fonts/opensans_regular.ttf"); @@ -46,7 +53,6 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { QFontDatabase::addApplicationFont("../assets/fonts/opensans_semibold.ttf"); // no outline to prevent the focus rectangle - setLayout(main_layout); setStyleSheet(R"( * { font-family: Inter; @@ -55,29 +61,19 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { )"); } -void MainWindow::offroadTransition(bool offroad){ - if(!offroad){ - closeSettings(); - } -} - void MainWindow::openSettings() { main_layout->setCurrentWidget(settingsWindow); } void MainWindow::closeSettings() { - if(onboardingDone) { - main_layout->setCurrentWidget(homeWindow); + main_layout->setCurrentWidget(homeWindow); + + if (QUIState::ui_state.scene.started) { + emit homeWindow->showSidebar(false); } } -void MainWindow::reviewTrainingGuide() { - onboardingDone = false; - main_layout->setCurrentWidget(onboardingWindow); - onboardingWindow->updateActiveScreen(); -} - -bool MainWindow::eventFilter(QObject *obj, QEvent *event){ +bool MainWindow::eventFilter(QObject *obj, QEvent *event) { // wake screen on tap if (event->type() == QEvent::MouseButtonPress) { device.setAwake(true, true); diff --git a/selfdrive/ui/qt/window.h b/selfdrive/ui/qt/window.h index 5a40e94bb..069831cff 100644 --- a/selfdrive/ui/qt/window.h +++ b/selfdrive/ui/qt/window.h @@ -6,18 +6,18 @@ #include "selfdrive/ui/qt/home.h" #include "selfdrive/ui/qt/offroad/onboarding.h" #include "selfdrive/ui/qt/offroad/settings.h" -#include "selfdrive/ui/ui.h" class MainWindow : public QWidget { Q_OBJECT -protected: - bool eventFilter(QObject *obj, QEvent *event) override; - public: explicit MainWindow(QWidget *parent = 0); private: + bool eventFilter(QObject *obj, QEvent *event) override; + void openSettings(); + void closeSettings(); + Device device; QUIState qs; @@ -25,11 +25,4 @@ private: HomeWindow *homeWindow; SettingsWindow *settingsWindow; OnboardingWindow *onboardingWindow; - bool onboardingDone = false; - -public slots: - void offroadTransition(bool offroad); - void openSettings(); - void closeSettings(); - void reviewTrainingGuide(); }; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 5468a0863..62f621de4 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -1,10 +1,10 @@ #include "selfdrive/ui/ui.h" -#include -#include #include +#include #include +#include #include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" @@ -85,7 +85,7 @@ static void update_line_data(const UIState *s, const cereal::ModelDataV2::XYZTDa v += calib_frame_to_full_frame(s, line_x[i], line_y[i] + y_off, line_z[i] + z_off, v); } pvd->cnt = v - pvd->v; - assert(pvd->cnt < std::size(pvd->v)); + assert(pvd->cnt <= std::size(pvd->v)); } static void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) { @@ -121,7 +121,7 @@ static void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) { update_line_data(s, model_position, 0.5, 1.22, &scene.track_vertices, max_idx); } -static void update_sockets(UIState *s){ +static void update_sockets(UIState *s) { s->sm->update(0); } @@ -134,7 +134,7 @@ static void update_state(UIState *s) { scene.engageable = sm["controlsState"].getControlsState().getEngageable(); scene.dm_active = sm["driverMonitoringState"].getDriverMonitoringState().getIsActiveMode(); } - if (sm.updated("radarState")) { + if (sm.updated("radarState") && s->vg) { std::optional line; if (sm.rcv_frame("modelV2") > 0) { line = sm["modelV2"].getModelV2().getPosition(); @@ -158,7 +158,7 @@ static void update_state(UIState *s) { } } } - if (sm.updated("modelV2")) { + if (sm.updated("modelV2") && s->vg) { update_model(s, sm["modelV2"].getModelV2()); } if (sm.updated("pandaState")) { @@ -168,15 +168,6 @@ static void update_state(UIState *s) { } else if ((s->sm->frame - s->sm->rcv_frame("pandaState")) > 5*UI_FREQ) { scene.pandaType = cereal::PandaState::PandaType::UNKNOWN; } - if (sm.updated("ubloxGnss")) { - auto data = sm["ubloxGnss"].getUbloxGnss(); - if (data.which() == cereal::UbloxGnss::MEASUREMENT_REPORT) { - scene.satelliteCount = data.getMeasurementReport().getNumMeas(); - } - } - if (sm.updated("gpsLocationExternal")) { - scene.gpsAccuracy = sm["gpsLocationExternal"].getGpsLocationExternal().getAccuracy(); - } if (sm.updated("carParams")) { scene.longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl(); } @@ -184,12 +175,12 @@ static void update_state(UIState *s) { for (auto sensor : sm["sensorEvents"].getSensorEvents()) { if (!scene.started && sensor.which() == cereal::SensorEventData::ACCELERATION) { auto accel = sensor.getAcceleration().getV(); - if (accel.totalSize().wordCount){ // TODO: sometimes empty lists are received. Figure out why + if (accel.totalSize().wordCount) { // TODO: sometimes empty lists are received. Figure out why scene.accel_sensor = accel[2]; } } else if (!scene.started && sensor.which() == cereal::SensorEventData::GYRO_UNCALIBRATED) { auto gyro = sensor.getGyroUncalibrated().getV(); - if (gyro.totalSize().wordCount){ + if (gyro.totalSize().wordCount) { scene.gyro_sensor = gyro[1]; } } @@ -199,16 +190,16 @@ static void update_state(UIState *s) { auto camera_state = sm["roadCameraState"].getRoadCameraState(); float max_lines = Hardware::EON() ? 5408 : 1757; - float gain = camera_state.getGainFrac(); + float gain = camera_state.getGain(); if (Hardware::TICI()) { - // gainFrac can go up to 4, with another 2.5x multiplier based on globalGain. Scale back to 0 - 1 - gain *= (camera_state.getGlobalGain() > 100 ? 2.5 : 1.0) / 10.0; + // Max gain is 4 * 2.5 (High Conversion Gain) + gain /= 10.0; } scene.light_sensor = std::clamp((1023.0 / max_lines) * (max_lines - camera_state.getIntegLines() * gain), 0.0, 1023.0); } - scene.started = sm["deviceState"].getDeviceState().getStarted(); + scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition; } static void update_params(UIState *s) { @@ -221,14 +212,14 @@ static void update_params(UIState *s) { static void update_vision(UIState *s) { if (!s->vipc_client->connected && s->scene.started) { - if (s->vipc_client->connect(false)){ + if (s->vipc_client->connect(false)) { ui_init_vision(s); } } - if (s->vipc_client->connected){ + if (s->vipc_client->connected) { VisionBuf * buf = s->vipc_client->recv(); - if (buf != nullptr){ + if (buf != nullptr) { s->last_frame = buf; } else if (!Hardware::PC()) { LOGE("visionIPC receive timeout"); @@ -265,7 +256,7 @@ static void update_status(UIState *s) { } // Choose vision ipc client - if (s->wide_camera){ + if (s->wide_camera) { s->vipc_client = s->vipc_client_wide; } else { s->vipc_client = s->vipc_client_rear; @@ -280,9 +271,8 @@ static void update_status(UIState *s) { QUIState::QUIState(QObject *parent) : QObject(parent) { ui_state.sm = std::make_unique>({ - "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "liveLocationKalman", - "pandaState", "carParams", "driverMonitoringState", "sensorEvents", "carState", "ubloxGnss", - "gpsLocationExternal", "roadCameraState", + "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState", + "pandaState", "carParams", "driverMonitoringState", "sensorEvents", "carState", "liveLocationKalman", }); ui_state.fb_w = vwp_w; diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index a8bcccf3d..db782c0a8 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -34,7 +34,7 @@ // TODO: this is also hardcoded in common/transformations/camera.py // TODO: choose based on frame input size const float y_offset = Hardware::TICI() ? 150.0 : 0.0; -const float zoom = Hardware::TICI() ? 2912.8 : 2138.5; +const float ZOOM = Hardware::TICI() ? 2912.8 : 2138.5; typedef struct Rect { int x, y, w, h; @@ -83,10 +83,6 @@ typedef struct UIScene { cereal::PandaState::PandaType pandaType; - // gps - int satelliteCount; - float gpsAccuracy; - // modelV2 float lane_line_probs[4]; float road_edge_stds[2]; @@ -136,7 +132,6 @@ typedef struct UIState { Rect video_rect, viz_rect; float car_space_transform[6]; bool wide_camera; - float zoom; } UIState; diff --git a/selfdrive/updated.py b/selfdrive/updated.py index ad2d88010..cfe57bee6 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -39,7 +39,6 @@ from common.params import Params from selfdrive.hardware import EON, TICI, HARDWARE from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.alertmanager import set_offroad_alert -from selfdrive.hardware.tici.agnos import flash_agnos_update LOCK_FILE = os.getenv("UPDATER_LOCK_FILE", "/tmp/safe_staging_overlay.lock") STAGING_ROOT = os.getenv("UPDATER_STAGING_ROOT", "/data/safe_staging") @@ -93,8 +92,8 @@ def set_consistent_flag(consistent: bool) -> None: consistent_file = Path(os.path.join(FINALIZED, ".overlay_consistent")) if consistent: consistent_file.touch() - elif not consistent and consistent_file.exists(): - consistent_file.unlink() + elif not consistent: + consistent_file.unlink(missing_ok=True) os.sync() @@ -220,6 +219,8 @@ def finalize_update() -> None: def handle_agnos_update(wait_helper): + from selfdrive.hardware.tici.agnos import flash_agnos_update, get_target_slot_number + cur_version = HARDWARE.get_os_version() updated_version = run(["bash", "-c", r"unset AGNOS_VERSION && source launch_env.sh && \ echo -n $AGNOS_VERSION"], OVERLAY_MERGED).strip() @@ -235,7 +236,8 @@ def handle_agnos_update(wait_helper): set_offroad_alert("Offroad_NeosUpdate", True) manifest_path = os.path.join(OVERLAY_MERGED, "selfdrive/hardware/tici/agnos.json") - flash_agnos_update(manifest_path, cloudlog) + target_slot_number = get_target_slot_number() + flash_agnos_update(manifest_path, target_slot_number, cloudlog) set_offroad_alert("Offroad_NeosUpdate", False) @@ -354,8 +356,7 @@ def main(): wait_helper.sleep(30) overlay_init = Path(os.path.join(BASEDIR, ".overlay_init")) - if overlay_init.exists(): - overlay_init.unlink() + overlay_init.unlink(missing_ok=True) first_run = True last_fetch_time = 0 @@ -404,9 +405,11 @@ def main(): returncode=e.returncode ) exception = f"command failed: {e.cmd}\n{e.output}" + overlay_init.unlink(missing_ok=True) except Exception as e: cloudlog.exception("uncaught updated exception, shouldn't happen") exception = str(e) + overlay_init.unlink(missing_ok=True) set_params(new_version, update_failed_count, exception) wait_helper.sleep(60)