diff --git a/.gitignore b/.gitignore index 38b208e41cc3d8..70ad45c3202958 100644 --- a/.gitignore +++ b/.gitignore @@ -2,7 +2,9 @@ .tags .ipynb_checkpoints .idea +.sconsign.dblite model2.png +a.out *.DSYM *.d @@ -26,5 +28,7 @@ selfdrive/boardd/boardd selfdrive/logcatd/logcatd selfdrive/proclogd/proclogd selfdrive/ui/ui +selfdrive/test/tests/plant/out /src/ +one diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 00000000000000..a65360ebe736c5 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,18 @@ +# How to contribute + +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 [slack](https://slack.comma.ai). A lot of documentation is available on our [medium](https://medium.com/@comma_ai/) + +## Getting Started + + * Join our slack [slack.comma.ai](https://slack.comma.ai) + * Make sure you have a [GitHub account](https://github.com/signup/free) + * Fork [our repositories](https://github.com/commaai) on GitHub + +## 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. + +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). You might also be eligible for a bounty. See our bounties at [comma.ai/bounties.html](https://comma.ai/bounties.html) + diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index 98e1c0abf5555d..2428249fae61ee 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -2,7 +2,7 @@ FROM ubuntu:16.04 ENV PYTHONUNBUFFERED 1 RUN apt-get update && apt-get install -y build-essential clang vim screen wget bzip2 git libglib2.0-0 python-pip capnproto libcapnp-dev libzmq5-dev libffi-dev libusb-1.0-0 -RUN pip install numpy==1.11.2 scipy==0.18.1 matplotlib +RUN pip install numpy==1.11.2 scipy==0.18.1 matplotlib==2.1.2 COPY requirements_openpilot.txt /tmp/ RUN pip install -r /tmp/requirements_openpilot.txt @@ -17,3 +17,5 @@ COPY ./phonelibs /tmp/openpilot/phonelibs COPY ./pyextra /tmp/openpilot/pyextra RUN mkdir -p /tmp/openpilot/selfdrive/test/out +RUN make -C /tmp/openpilot/selfdrive/controls/lib/longitudinal_mpc clean +RUN make -C /tmp/openpilot/selfdrive/controls/lib/lateral_mpc clean diff --git a/LICENSE.openpilot b/LICENSE similarity index 96% rename from LICENSE.openpilot rename to LICENSE index 8a6c6976b70de3..7dafa9443b1545 100644 --- a/LICENSE.openpilot +++ b/LICENSE @@ -1,4 +1,4 @@ -Copyright (c) 2016, Comma.ai, Inc. +Copyright (c) 2018, Comma.ai, Inc. Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: diff --git a/README.md b/README.md index 01ca0d824831b0..394ae9d749cdaa 100644 --- a/README.md +++ b/README.md @@ -1,91 +1,186 @@ +[![](https://i.imgur.com/UetIFyH.jpg)](#) + Welcome to openpilot ====== -[openpilot](http://github.com/commaai/openpilot) is an open source driving agent. +[openpilot](http://github.com/commaai/openpilot) is an open source driving agent. Currently, it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for selected Honda, Toyota, Acura, Lexus, Chevrolet, Hyundai, Kia. It's about on par with Tesla Autopilot and GM Super Cruise, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan). + +The openpilot codebase has been written to be concise and to enable rapid prototyping. We look forward to your contributions - improving real vehicle automation has never been easier. + +Table of Contents +======================= -Currently it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for Hondas, Acuras and Toyotas. It's about on par with Tesla Autopilot at launch, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan). +* [Community](#community) +* [Hardware](#hardware) +* [Supported Cars](#supported-cars) +* [Community Maintained Cars](#community-maintained-cars) +* [In Progress Cars](#in-progress-cars) +* [How can I add support for my car?](#how-can-i-add-support-for-my-car-) +* [Directory structure](#directory-structure) +* [User Data / chffr Account / Crash Reporting](#user-data-chffr-account-crash-reporting) +* [Testing on PC](#testing-on-pc) +* [Contributing](#contributing) +* [Licensing](#licensing) -The openpilot codebase has been written to be concise and enable rapid prototyping. We look forward to your contributions - improving real vehicle automation has never been easier. +--- + +Community +------ -Here are [some](https://www.youtube.com/watch?v=9OwTJFuDI7g) [videos](https://www.youtube.com/watch?v=64Wvt5pYQmE) [of](https://www.youtube.com/watch?v=6IW7Nejsr3A) [it](https://www.youtube.com/watch?v=-VN1YcC83nA) [running](https://www.youtube.com/watch?v=EQJZvVeihZk). And a really cool [tutorial](https://www.youtube.com/watch?v=PwOnsT2UW5o). +openpilot is developed by [comma.ai](https://comma.ai/) and users like you. + +We have a [Twitter you should follow](https://twitter.com/comma_ai). + +Also, we have a several thousand people community on [slack](https://slack.comma.ai). + + + + + + + + + + + + + + +
Hardware ------ -Right now openpilot supports the [NEO research platform](http://github.com/commaai/neo) and the [EON Dashcam DevKit](https://shop.comma.ai/products/eon-dashcam-devkit). We'd like to support other platforms as well. +Right now openpilot supports the [EON Dashcam DevKit](https://comma.ai/shop/products/eon-dashcam-devkit). We'd like to support other platforms as well. Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` during NEOS setup. Supported Cars ------ -- Acura ILX 2016 with AcuraWatch Plus - - Due to use of the cruise control for gas, it can only be enabled above 25 mph - -- Honda Civic 2016-2017 with Honda Sensing - - Due to limitations in steering firmware, steering is disabled below 12 mph - - Note that the hatchback model is not supported - -- Honda CR-V Touring 2015-2016 - - Can only be enabled above 25 mph +| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | Giraffe | +| ---------------------| ------------------------| ---------------------| --------| ---------------| -----------------| ---------------|-------------------| +| Acura | ILX 2016-17 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | Nidec | +| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph1| 12mph | Nidec | +| Chevrolet3| Malibu 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7| +| Chevrolet3| Volt 2017-18 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7| +| GMC3| Acadia Denali 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7| +| Holden3 | Astra 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7| +| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | Bosch | +| Honda | Civic 2016-18 | Honda Sensing | Yes | Yes | 0mph | 12mph | Nidec | +| Honda | Civic 2017-18 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch | +| Honda | CR-V 2015-16 | Touring | Yes | Yes | 25mph1| 12mph | Nidec | +| Honda | CR-V 2017-18 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch | +| Honda | Odyssey 2017-19 | Honda Sensing | Yes | Yes | 25mph1| 0mph | Inverted Nidec | +| Honda | Pilot 2016-18 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec | +| Honda | Pilot 2019 | All | Yes | Yes | 25mph1| 12mph | Inverted Nidec | +| Honda | Ridgeline 2017-18 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec | +| Hyundai | Santa Fe 2019 | All | Yes | Stock | 0mph | 0mph | Custom6| +| Hyundai | Elantra 2017 | SCC + LKAS | Yes | Stock | 19mph | 34mph | Custom6| +| Hyundai | Genesis 2018 | All | Yes | Stock | 19mph | 34mph | Custom6| +| Kia | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | Custom6| +| Kia | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom6| +| Lexus | RX Hybrid 2016-18 | All | Yes | Yes2| 0mph | 0mph | Toyota | +| Toyota | Camry 20184 | All | Yes | Stock | 0mph5 | 0mph | Toyota | +| Toyota | C-HR 2017-184| All | Yes | Stock | 0mph | 0mph | Toyota | +| Toyota | Corolla 2017-18 | All | Yes | Yes2| 20mph | 0mph | Toyota | +| Toyota | Highlander 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota | +| Toyota | Highlander Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | Toyota | +| Toyota | Prius 2016 | TSS-P | Yes | Yes2| 0mph | 0mph | Toyota | +| Toyota | Prius 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota | +| Toyota | Prius Prime 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota | +| Toyota | Rav4 2016 | TSS-P | Yes | Yes2| 20mph | 0mph | Toyota | +| Toyota | Rav4 2017-18 | All | Yes | Yes2| 20mph | 0mph | Toyota | +| Toyota | Rav4 Hybrid 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota | + +1[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma.ai](https://comma.ai)*** +2When disconnecting the Driver Support Unit (DSU), otherwise longitudinal control is stock ACC. For DSU locations, see [Toyota Wiki page](https://community.comma.ai/wiki/index.php/Toyota) +3[GM installation guide](https://zoneos.com/volt/). +4It needs an extra 120Ohm resistor ([pic1](https://i.imgur.com/CmdKtTP.jpg), [pic2](https://i.imgur.com/s2etUo6.jpg)) on bus 3 and giraffe switches set to 01X1 (11X1 for stock LKAS), where X depends on if you have the [comma power](https://comma.ai/shop/products/power/). +528mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control. +6Open sourced [Hyundai Giraffe](https://github.com/commaai/neo/tree/master/giraffe/hyundai) is designed ofor the 2019 Sante Fe; pinout may differ for other Hyundais.
+7Community built Giraffe, find more information here, [GM Giraffe](https://zoneos.com/shop/)
+ +Community Maintained Cars +------ -- Toyota RAV-4 2016+ non-hybrid with TSS-P - - By default it uses stock Toyota ACC for longitudinal control - - openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Rav4_.28for_openpilot.29) and can be enabled above 20 mph +| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | Giraffe | +| ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- | ------------------| +| Honda | Fit 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Inverted Nidec | +| Tesla | Model S 2012 | All | Yes | Not yet | Not applicable | 0mph | Custom8| +| Tesla | Model S 2013 | All | Yes | Not yet | Not applicable | 0mph | Custom8| -- Toyota Prius 2017 (alpha!) - - By default it uses stock Toyota ACC for longitudinal control - - openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Prius_.28for_openpilot.29) - - Lateral control needs improvements +[[Honda Fit Pull Request]](https://github.com/commaai/openpilot/pull/266).
+[[Tesla Model S Pull Request]](https://github.com/commaai/openpilot/pull/246)
+8Community built Giraffe, find more information here [Community Tesla Giraffe](https://github.com/jeankalud/neo/tree/tesla_giraffe/giraffe/tesla)
-- Toyota RAV-4 2017 hybrid (alpha!) - - By default it uses stock Toyota ACC for longitudinal control - - openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Rav4_.28for_openpilot.29) and can do stop and go +Community Maintained Cars are not confirmed by comma.ai to meet our [safety model](https://github.com/commaai/openpilot/blob/devel/SAFETY.md). Be extra cautious using them. In Progress Cars ------ -- Probably all TSS-P Toyota with Steering Assist. +- All TSS-P Toyota with Steering Assist. - 'Full Speed Range Dynamic Radar Cruise Control' is required to enable stop-and-go. Only the Prius, Camry and C-HR have this option. - Even though the Tundra, Sequoia and the Land Cruiser have TSS-P, they don't have Steering Assist and are not supported. - -Community WIP Cars + - Only remaining Toyota cars with no port yet are the Avalon and the Sienna. +- All LSS-P Lexus with Steering Assist or Lane Keep Assist. + - 'All-Speed Range Dynamic Radar Cruise Control' is required to enable stop-and-go. Only the GS, GSH, F, RX, RXH, LX, NX, NXH, LC, LCH, LS, LSH have this option. + - Even though the LX have TSS-P, it does not have Steering Assist and is not supported. +- All Hyundai with SmartSense. +- All Kia with SCC and LKAS. + +How can I add support for my car? ------ -- [Chevy Volt 2016-2018 Premier with Driver Confidence II](https://github.com/commaai/openpilot/pull/104) +If your car has adaptive cruise control and lane keep assist, you are in luck. Using a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle/) and [cabana](https://community.comma.ai/cabana/), you can understand how to make your car drive by wire. -- [Classic Tesla Model S (pre-AP)](https://github.com/commaai/openpilot/pull/145) +We've written guides 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. These guides might help you after you have the basics figured out. -- [Honda Odyssey 2018 with Honda Sensing](https://github.com/commaai/openpilot/pull/155) +- BMW, Audi, Volvo, and Mercedes all use [FlexRay](https://en.wikipedia.org/wiki/FlexRay) and are unlikely to be supported any time soon. +- We put time into a Ford port, but the steering has a 10 second cutout limitation that makes it unusable. +- The 2016-2017 Honda Accord uses a custom signaling protocol for steering that's unlikely to ever be upstreamed. -- [Honda Pilot 2017 with Honda Sensing](https://github.com/commaai/openpilot/pull/161) +Directory structure +------ + . + ├── apk # The apk files used for the UI + ├── cereal # The messaging spec used for all logs on EON + ├── common # Library like functionality we've developed here + ├── installer/updater # Manages auto-updates of openpilot + ├── opendbc # Files showing how to interpret data from cars + ├── panda # Code used to communicate on CAN and LIN + ├── phonelibs # Libraries used on EON + ├── pyextra # Libraries used on EON + └── selfdrive # Code needed to drive the car + ├── assets # Fonts and images for UI + ├── boardd # Daemon to talk to the board + ├── can # Helpers for parsing CAN messages + ├── car # Car specific code to read states and control actuators + ├── common # Shared C/C++ code for the daemons + ├── controls # Perception, planning and controls + ├── debug # Tools to help you debug and do car ports + ├── locationd # Soon to be home of precise location + ├── logcatd # Android logcat as a service + ├── loggerd # Logger and uploader of car data + ├── proclogd # Logs information from proc + ├── sensord # IMU / GPS interface code + ├── test # Car simulator running code through virtual maneuvers + ├── ui # The UI + └── visiond # Embedded vision pipeline -- [Acura RDX 2018 with AcuraWatch Plus](https://github.com/commaai/openpilot/pull/162) +To understand how the services interact, see `selfdrive/service_list.yaml` -Directory structure +User Data / chffr Account / Crash Reporting ------ -- cereal -- The messaging spec used for all logs on the phone -- common -- Library like functionality we've developed here -- opendbc -- Files showing how to interpret data from cars -- panda -- Code used to communicate on CAN and LIN -- phonelibs -- Libraries used on the phone -- selfdrive -- Code needed to drive the car - - assets -- Fonts for ui - - boardd -- Daemon to talk to the board - - car -- Code that talks to the car and implements CarInterface - - common -- Shared C/C++ code for the daemons - - controls -- Python controls (PID loops etc) for the car - - debug -- Tools to help you debug and do car ports - - logcatd -- Android logcat as a service - - loggerd -- Logger and uploader of car data - - proclogd -- Logs information from proc - - radar -- Code that talks to the radar and implements RadarInterface - - sensord -- IMU / GPS interface code - - test/plant -- Car simulator running code through virtual maneuvers - - ui -- The UI - - visiond -- embedded vision pipeline +By default, openpilot creates an account and includes a client for chffr, our dashcam app. We use your data to train better models and improve openpilot for everyone. -To understand how the services interact, see `selfdrive/service_list.yaml` +It's open source software, so you are free to disable it if you wish. + +It logs the road facing camera, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +The user facing camera is only logged if you explicitly opt-in in settings. +It does not log the microphone. + +By using it, you agree to [our privacy policy](https://community.comma.ai/privacy.html). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma.ai. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma.ai for the use of this data. Testing on PC ------ @@ -97,45 +192,30 @@ There is rudimentary infrastructure to run a basic simulation and generate a rep ./run_docker_tests.sh ``` -The results are written to `selfdrive/test/plant/out/index.html` +The resulting plots are displayed in `selfdrive/test/tests/plant/out/longitudinal/index.html` More extensive testing infrastructure and simulation environments are coming soon. -Adding Car Support ------- - -comma.ai offers [bounties](http://comma.ai/bounties.html) for adding additional car support. - -CR-V Touring support came in through this program. Chevy Volt is close. Accord is close as well. - -User Data / chffr Account / Crash Reporting ------- - -By default openpilot creates an account and includes a client for chffr, our dashcam app. We use your data to train better models and improve openpilot for everyone. - -It's open source software, so you are free to disable it if you wish. - -It logs the road facing camera, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. -It does not log the user facing camera or the microphone. - -By using it, you agree to [our privacy policy](https://beta.comma.ai/privacy.html). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma.ai. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma.ai for the use of this data. Contributing ------ We welcome both pull requests and issues on -[github](http://github.com/commaai/openpilot). See the TODO file for a list of -good places to start. +[github](http://github.com/commaai/openpilot). Bug fixes and new car ports encouraged. -Want to get paid to work on openpilot? [comma.ai is hiring](http://comma.ai/positions.html) +Want to get paid to work on openpilot? [comma.ai is hiring](https://comma.ai/jobs/) Licensing ------ -openpilot is released under the MIT license. +openpilot is released under the MIT license. Some parts of the software are released under other licenses as specified. Any user of this software shall indemnify and hold harmless Comma.ai, Inc. and its directors, officers, employees, agents, stockholders, affiliates, subcontractors and customers from and against all allegations, claims, actions, suits, demands, damages, liabilities, obligations, losses, settlements, judgments, costs and expenses (including without limitation attorneys’ fees and costs) which arise out of, relate to or result from any use of this software by user. **THIS IS ALPHA QUALITY SOFTWARE FOR RESEARCH PURPOSES ONLY. THIS IS NOT A PRODUCT. YOU ARE RESPONSIBLE FOR COMPLYING WITH LOCAL LAWS AND REGULATIONS. NO WARRANTY EXPRESSED OR IMPLIED.** + +--- + + diff --git a/README_chffrplus.md b/README_chffrplus.md new file mode 100644 index 00000000000000..dc13e8c3f264c6 --- /dev/null +++ b/README_chffrplus.md @@ -0,0 +1,36 @@ +Welcome to chffrplus +====== + +[chffrplus](https://github.com/commaai/chffrplus) is an open source dashcam. + +This is the shipping reference software for the comma EON Dashcam DevKit. It keeps many of the niceities of [openpilot](https://github.com/commaai/openpilot), like high quality sensors, great camera, and good autostart and stop. Though unlike openpilot, it cannot control your car. chffrplus can interface with your car through a [panda](https://shop.comma.ai/products/panda-obd-ii-dongle), but just like our dashcam app [chffr](https://getchffr.com/), it is read only. + +It integrates with the rest of the comma ecosystem, so you can view your drives on the [chffr](https://getchffr.com/) app for Android or iOS, and reverse engineer your car with [cabana](https://community.comma.ai/cabana/?demo=1). + + +Hardware +------ + +Right now chffrplus supports the [EON Dashcam DevKit](https://shop.comma.ai/products/eon-dashcam-devkit) for hardware to run on. + +Install chffrplus on a EON device by entering ``https://chffrplus.comma.ai`` during NEOS setup. + + +User Data / chffr Account / Crash Reporting +------ + +By default chffrplus creates an account and includes a client for chffr, our dashcam app. + +It's open source software, so you are free to disable it if you wish. + +It logs the road facing camera, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +It does not log the user facing camera or the microphone. + +By using it, you agree to [our privacy policy](https://beta.comma.ai/privacy.html). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma.ai. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma.ai for the use of this data. + + +Licensing +------ + +chffrplus is released under the MIT license. + diff --git a/RELEASES.md b/RELEASES.md index fbcabd13d3f586..eef675a304271c 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,159 @@ +Version 0.5.6 (2018-11-16) +======================== + * Refresh settings layout and add feature descriptions + * In Honda, keep stock camera on for logging and extra stock features; new openpilot giraffe setting is 0111! + * In Toyota, option to keep stock camera on for logging and extra stock features (e.g. AHB); 120Ohm resistor required on giraffe. + * Improve camera calibration stability + * More tuning to Honda positive accelerations + * Reduce brake pump use on Hondas + * Chevrolet Malibu support thanks to tylergets! + * Holden Astra support thanks to AlexHill! + +Version 0.5.5 (2018-10-20) +======================== + * Increase allowed Honda positive accelerations + * Fix sporadic unexpected braking when passing semi-trucks in Toyota + * Fix gear reading bug in Hyundai Elantra thanks to emmertex! + +Version 0.5.4 (2018-09-25) +======================== + * New Driving Model + * New Driver Monitoring Model + * Improve longitudinal mpc in mid-low speed braking + * Honda Accord hybrid support thanks to energee! + * Ship mpc binaries and sensibly reduce build time + * Calibration more stable + * More Hyundai and Kia cars supported thanks to emmertex! + * Various GM Volt improvements thanks to vntarasov! + +Version 0.5.3 (2018-09-03) +======================== + * Hyundai Santa Fe support! + * Honda Pilot 2019 support thanks to energee! + * Toyota Highlander support thanks to daehahn! + * Improve steering tuning for Honda Odyssey + +Version 0.5.2 (2018-08-16) +======================== + * New calibration: more accurate, a lot faster, open source! + * Enable orbd + * Add little endian support to CAN packer + * Fix fingerprint for Honda Accord 1.5T + * Improve driver monitoring model + +Version 0.5.1 (2018-08-01) +======================== + * Fix radar error on Civic sedan 2018 + * Improve thermal management logic + * Alpha Toyota C-HR and Camry support! + * Auto-switch Driver Monitoring to 3 min counter when inaccurate + +Version 0.5 (2018-07-11) +======================== + * Driver Monitoring (beta) option in settings! + * Make visiond, loggerd and UI use less resources + * 60 FPS UI + * Better car parameters for most cars + * New sidebar with stats + * Remove Waze and Spotify to free up system resources + * Remove rear view mirror option + * Calibration 3x faster + +Version 0.4.7.2 (2018-06-25) +========================== + * Fix loggerd lag issue + * No longer prompt for updates + * Mitigate right lane hugging for properly mounted EON (procedure on wiki) + +Version 0.4.7.1 (2018-06-18) +========================== + * Fix Acura ILX steer faults + * Fix bug in mock car + +Version 0.4.7 (2018-06-15) +========================== + * New model! + * GM Volt (and CT6 lateral) support! + * Honda Bosch lateral support! + * Improve actuator modeling to reduce lateral wobble + * Minor refactor of car abstraction layer + * Hack around orbd startup issue + +Version 0.4.6 (2018-05-18) +========================== + * NEOSv6 required! Will autoupdate + * Stability improvements + * Fix all memory leaks + * Update C++ compiler to clang6 + * Improve front camera exposure + +Version 0.4.5 (2018-04-27) +========================== + * Release notes added to the update popup + * Improve auto shut-off logic to disallow empty battery + * Added onboarding instructions + * Include orbd, the first piece of new calibration algorithm + * Show remaining upload data instead of file numbers + * Fix UI bugs + * Fix memory leaks + +Version 0.4.4 (2018-04-13) +========================== + * EON are flipped! Flip your EON's mount! + * Alpha Honda Ridgeline support thanks to energee! + * Support optional front camera recording + * Upload over cellular toggle now applies to all files, not just video + * Increase acceleration when closing lead gap + * User now prompted for future updates + * NEO no longer supported :( + +Version 0.4.3.2 (2018-03-29) +============================ + * Improve autofocus + * Improve driving when only one lane line is detected + * Added fingerprint for Toyota Corolla LE + * Fixed Toyota Corolla steer error + * Full-screen driving UI + * Improved path drawing + +Version 0.4.3.1 (2018-03-19) +============================ + * Improve autofocus + * Add check for MPC solution error + * Make first distracted warning visual only + +Version 0.4.3 (2018-03-13) +========================== + * Add HDR and autofocus + * Update UI aesthetic + * Grey panda works in Waze + * Add alpha support for 2017 Honda Pilot + * Slight increase in acceleration response from stop + * Switch CAN sending to use CANPacker + * Fix pulsing acceleration regression on Honda + * Fix openpilot bugs when stock system is in use + * Change starting logic for chffrplus to use battery voltage + +Version 0.4.2 (2018-02-05) +========================== + * Add alpha support for 2017 Lexus RX Hybrid + * Add alpha support for 2018 ACURA RDX + * Updated fingerprint to include Toyota Rav4 SE and Prius Prime + * Bugfixes for Acura ILX and Honda Odyssey + +Version 0.4.1 (2018-01-30) +========================== + * Add alpha support for 2017 Toyota Corolla + * Add alpha support for 2018 Honda Odyssey with Honda Sensing + * Add alpha support for Grey Panda + * Refactored car abstraction layer to make car ports easier + * Increased steering torque limit on Honda CR-V by 30% + +Version 0.4.0.2 (2018-01-18) +========================== + * Add focus adjustment slider + * Minor bugfixes + Version 0.4.0.1 (2017-12-21) ========================== * New UI to match chffrplus diff --git a/SAFETY.md b/SAFETY.md index 125705ad0447e7..a2f77a55093901 100644 --- a/SAFETY.md +++ b/SAFETY.md @@ -6,7 +6,10 @@ Like other ACC and LKA systems, openpilot requires the driver to be alert and to pay attention at all times. We repeat, **driver alertness is necessary, but not sufficient, for openpilot to be used safely**. -Even with an attentive driver, we must make further efforts for the system to be +In order to enforce driver alertness, openpilot includes a driver monitoring feature +that alerts the driver when distracted. + +However, even with an attentive driver, we must make further efforts for the system to be safe. We have designed openpilot with two other safety considerations. 1. The driver must always be capable to immediately retake manual control of the vehicle, @@ -20,7 +23,7 @@ Following are details of the car specific safety implementations: Honda/Acura ------ - - While the system is engaged, gas, brake and steer limits are subject to the same limits used by + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by the stock system. - Without an interceptor, the gas is controlled by the Powertrain Control Module (PCM). @@ -28,46 +31,79 @@ Honda/Acura interceptor, the gas is clipped to 60%. - The brake is controlled by the 0x1FA CAN message. This message allows full - braking, although the board and the software clip it to 1/4th of the max. - This is around .3g of braking. + braking, although the panda firmware and openpilot clip it to 1/4th of the max. + This is approximately 0.3g of braking. - Steering is controlled by the 0xE4 CAN message. The Electronic Power Steering (EPS) controller in the car limits the torque to a very small amount, so regardless of the message, the controller cannot jerk the wheel. - Brake and gas pedal pressed signals are contained in the 0x17C CAN message. A rising edge of - either signal triggers a disengagement, which is enforced by the board and in software. The - green led on the board signifies if the board is allowing control messages. + either signals triggers a disengagement, which is enforced by the panda firmware and by openpilot. The + white led on the panda signifies if the panda is allowing control messages. - Honda CAN uses both a counter and a checksum to ensure integrity and prevent replay of the same message. -Toyota +Toyota/Lexus ------ - - While the system is engaged, gas, brake and steer limits are subject to the same limits used by + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by the stock system. - - With the stock Driving Support Unit (DSU) enabled, the acceleration is controlled - by the stock system and is subject to the stock adaptive cruise control limits. Without the - stock DSU connected, the acceleration command is controlled by the 0x343 CAN message and its - value is limited by the board and the software to between .3g of deceleration and .15g of - acceleration. The acceleration command is ignored by the Engine Control Module (ECM) while the - cruise control system is disengaged. - - - Steering torque is controlled through the 0x2E4 CAN message and it's limited by the board and in - software to a value of -1500 and 1500. In addition, the vehicle EPS unit will not respond to - commands outside these limits. A steering torque rate limit is enforced by the board and in - software so that the commanded steering torque must rise from 0 to max value no faster than - 1.5s. Commanded steering torque is limited by the board and in software to be no more than 500 + - With the stock Driving Support Unit (DSU) connected (or in DSU-less models like Camry and C-HR), + the acceleration is controlled by the stock system and is subject to the stock adaptive cruise + control limits. Without the stock DSU connected, the acceleration command is controlled by the + 0x343 CAN message and its value is limited between .3g of deceleration and .15g of acceleration + by the panda firmware and by openpilot. The acceleration command is ignored by the Engine Control + Module (ECM) while the cruise control system is disengaged. + + - Steering torque is controlled through the 0x2E4 CAN message and it's limited by the panda firmware and by + openpilot to a value between -1500 and 1500. In addition, the vehicle EPS unit will not respond to + commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by + openpilot, so that the commanded steering torque must rise from 0 to max value no faster than + 1.5s. Commanded steering torque is limited by the panda firmware and by openpilot to be no more than 350 units above the actual EPS generated motor torque to ensure limited differences between commanded and actual torques. - Brake and gas pedal pressed signals are contained in the 0x224 and 0x1D2 CAN messages, - respectively. A rising edge of either signal triggers a disengagement, which is enforced by the - board and in software. Additionally, the cruise control system disengages on the rising edge of + respectively. A rising edge of either signals triggers a disengagement, which is enforced by the + panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of the brake pedal pressed signal. - The cruise control system state is contained in the 0x1D2 message. No control messages are - allowed if the cruise control system is not active. This is enforced by the software and the - board. The green led on the board signifies if the board is allowing control messages. + allowed if the cruise control system is not active. This is enforced by openpilot and the + panda firmware. The white led on the panda signifies if the panda is allowing control messages. + +GM/Chevrolet +------ + + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by + the stock system. + + - The gas and regen are controlled by the 0x2CB message and it's limited by the panda firmware and by + openpilot to a value between 1404 and 3072. the minimum value correspond to a mild decel due to regen, + while 3072 correspond to approximately 0.18g of acceleration from stop. + + - The friction brakes are controlled by the 0x315 message and its value is limited by the panda firmware + and openpilot to 350. This is approximately 0.3g of braking. + + - Steering torque is controlled through the 0x180 CAN message and it's limited by the panda firmware and by + openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will not fault when + commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by + openpilot, so that the commanded steering torque must rise from 0 to max value no faster than + 0.75s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's + torque exceeds 12 units in the opposite dicrection to ensure limited applied torque against the + driver's will. + + - Brake pedal and gas pedal potentiometer signals are contained in the 0xF1 and 0x1A1 CAN messages, + respectively. A rising edge of either signals triggers a disengagement, which is enforced by the + panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of + the brake pedal pressed signal. The regen paddle pressed signal is in the 0xBD message. When the + regen paddle is pressed, a disengagement is enforced by both the firmware and by openpilot. + + - GM CAN uses both a counter and a checksum to ensure integrity and prevent + replay of the same message. + +**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/apk/ai.comma.plus.frame.apk b/apk/ai.comma.plus.frame.apk index 06fcf2a513f480..b44c0e5004e06c 100644 Binary files a/apk/ai.comma.plus.frame.apk and b/apk/ai.comma.plus.frame.apk differ diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index db04675cc8afbf..a9e5738a40cd3c 100644 Binary files a/apk/ai.comma.plus.offroad.apk and b/apk/ai.comma.plus.offroad.apk differ diff --git a/cereal/.gitignore b/cereal/.gitignore index 4f62b849d56cd0..57b5883f38d38d 100644 --- a/cereal/.gitignore +++ b/cereal/.gitignore @@ -1 +1,3 @@ gen +node_modules +package-lock.json diff --git a/cereal/Makefile b/cereal/Makefile index b384b4904efc51..b86fa68f585816 100644 --- a/cereal/Makefile +++ b/cereal/Makefile @@ -3,38 +3,46 @@ PWD := $(shell pwd) SRCS := log.capnp car.capnp GENS := gen/cpp/car.capnp.c++ gen/cpp/log.capnp.c++ +JS := gen/js/car.capnp.js gen/js/log.capnp.js UNAME_M ?= $(shell uname -m) # only generate C++ for docker tests ifneq ($(OPTEST),1) - GENS += gen/c/car.capnp.c gen/c/log.capnp.c gen/c/c++.capnp.h gen/c/java.capnp.h + GENS += gen/c/car.capnp.c gen/c/log.capnp.c gen/c/include/c++.capnp.h gen/c/include/java.capnp.h -# Dont build java on the phone... -ifeq ($(UNAME_M),x86_64) - GENS += gen/java/Car.java gen/java/Log.java -endif + ifeq ($(UNAME_M),x86_64) + GENS += gen/java/Car.java gen/java/Log.java + endif endif ifeq ($(UNAME_M),aarch64) -CAPNPC=PATH=$(PWD)/../phonelibs/capnp-cpp/aarch64/bin/:$$PATH capnpc + CAPNPC=PATH=$(PWD)/../phonelibs/capnp-cpp/aarch64/bin/:$$PATH capnpc else -CAPNPC=capnpc + CAPNPC=capnpc endif .PHONY: all all: $(GENS) +js: $(JS) .PHONY: clean clean: rm -rf gen + rm -rf node_modules + rm -rf package-lock.json gen/c/%.capnp.c: %.capnp @echo "[ CAPNPC C ] $@" mkdir -p gen/c/ $(CAPNPC) '$<' -o c:gen/c/ +gen/js/%.capnp.js: %.capnp + @echo "[ CAPNPC JavaScript ] $@" + mkdir -p gen/js/ + sh ./generate_javascript.sh + gen/cpp/%.capnp.c++: %.capnp @echo "[ CAPNPC C++ ] $@" mkdir -p gen/cpp/ @@ -46,7 +54,6 @@ gen/java/Car.java gen/java/Log.java: $(SRCS) $(CAPNPC) $^ -o java:gen/java # c-capnproto needs some empty headers -gen/c/c++.capnp.h gen/c/java.capnp.h: - mkdir -p gen/c/ +gen/c/include/c++.capnp.h gen/c/include/java.capnp.h: + mkdir -p gen/c/include touch '$@' - diff --git a/cereal/__init__.py b/cereal/__init__.py index 725c7f8f048a49..2d3b48526b2c34 100644 --- a/cereal/__init__.py +++ b/cereal/__init__.py @@ -4,17 +4,5 @@ CEREAL_PATH = os.path.dirname(os.path.abspath(__file__)) capnp.remove_import_hook() -if os.getenv("NEWCAPNP"): - import tempfile - import pyximport - - importers = pyximport.install(build_dir=os.path.join(tempfile.gettempdir(), ".pyxbld")) - try: - import cereal.gen.cython.log_capnp_cython as log - import cereal.gen.cython.car_capnp_cython as car - finally: - pyximport.uninstall(*importers) - del importers -else: - log = capnp.load(os.path.join(CEREAL_PATH, "log.capnp")) - car = capnp.load(os.path.join(CEREAL_PATH, "car.capnp")) +log = capnp.load(os.path.join(CEREAL_PATH, "log.capnp")) +car = capnp.load(os.path.join(CEREAL_PATH, "car.capnp")) diff --git a/cereal/car.capnp b/cereal/car.capnp index 63857ed744c631..2f25aa0d1ac02e 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -1,7 +1,7 @@ -using Cxx = import "c++.capnp"; +using Cxx = import "./include/c++.capnp"; $Cxx.namespace("cereal"); -using Java = import "java.capnp"; +using Java = import "./include/java.capnp"; $Java.package("ai.comma.openpilot.cereal"); $Java.outerClassname("Car"); @@ -42,7 +42,7 @@ struct CarEvent @0x9b1657f34caf3ad3 { speedTooLow @17; outOfSpace @18; overheat @19; - calibrationInProgress @20; + calibrationIncomplete @20; calibrationInvalid @21; controlsMismatch @22; pcmEnable @23; @@ -54,6 +54,24 @@ struct CarEvent @0x9b1657f34caf3ad3 { parkBrake @29; manualRestart @30; lowSpeedLockout @31; + plannerError @32; + ipasOverride @33; + debugAlert @34; + steerTempUnavailableMute @35; + resumeRequired @36; + preDriverDistracted @37; + promptDriverDistracted @38; + driverDistracted @39; + geofence @40; + driverMonitorOn @41; + driverMonitorOff @42; + preDriverUnresponsive @43; + promptDriverUnresponsive @44; + driverUnresponsive @45; + belowSteerSpeed @46; + calibrationProgress @47; + lowBattery @48; + invalidGiraffeHonda @49; } } @@ -97,6 +115,11 @@ struct CarState { buttonEvents @11 :List(ButtonEvent); leftBlinker @20 :Bool; rightBlinker @21 :Bool; + genericToggle @23 :Bool; + + # lock info + doorOpen @24 :Bool; + seatbeltUnlatched @25 :Bool; # which packets this state came from canMonoTimes @12: List(UInt64); @@ -160,6 +183,7 @@ struct RadarState { enum Error { commIssue @0; fault @1; + wrongConfig @2; } # similar to LiveTracks @@ -186,6 +210,7 @@ struct RadarState { struct CarControl { # must be true for any actuator commands to work enabled @0 :Bool; + active @7 :Bool; gasDEPRECATED @1 :Float32; brakeDEPRECATED @2 :Float32; @@ -202,6 +227,7 @@ struct CarControl { brake @1: Float32; # range from -1.0 - 1.0 steer @2: Float32; + steerAngle @3: Float32; } struct CruiseControl { @@ -235,13 +261,13 @@ struct CarControl { # these are the choices from the Honda # map as good as you can for your car none @0; - beepSingle @1; - beepTriple @2; - beepRepeated @3; - chimeSingle @4; - chimeDouble @5; - chimeRepeated @6; - chimeContinuous @7; + chimeEngage @1; + chimeDisengage @2; + chimeError @3; + chimeWarning1 @4; + chimeWarning2 @5; + chimeWarningRepeat @6; + chimePrompt @7; } } } @@ -250,19 +276,21 @@ struct CarControl { struct CarParams { carName @0 :Text; - radarName @1 :Text; + radarNameDEPRECATED @1 :Text; carFingerprint @2 :Text; - enableSteer @3 :Bool; - enableGas @4 :Bool; - enableBrake @5 :Bool; + enableSteerDEPRECATED @3 :Bool; + enableGasInterceptor @4 :Bool; + enableBrakeDEPRECATED @5 :Bool; enableCruise @6 :Bool; enableCamera @26 :Bool; enableDsu @27 :Bool; # driving support unit enableApgs @28 :Bool; # advanced parking guidance system minEnableSpeed @17 :Float32; + minSteerSpeed @49 :Float32; safetyModel @18 :Int16; + safetyParam @41 :Int16; steerMaxBP @19 :List(Float32); steerMaxV @20 :List(Float32); @@ -280,6 +308,13 @@ struct CarParams { honda @1; toyota @2; elm327 @3; + gm @4; + hondaBosch @5; + ford @6; + cadillac @7; + hyundai @8; + chrysler @9; + tesla @10; } # things about the car in the manual @@ -295,8 +330,12 @@ struct CarParams { tireStiffnessRear @14 :Float32; # [N/rad] rear tire coeff of stiff # Kp and Ki for the lateral control - steerKp @15 :Float32; - steerKi @16 :Float32; + steerKpBP @42 :List(Float32); + steerKpV @43 :List(Float32); + steerKiBP @44 :List(Float32); + steerKiV @45 :List(Float32); + steerKpDEPRECATED @15 :Float32; + steerKiDEPRECATED @16 :Float32; steerKf @25 :Float32; # Kp and Ki for the longitudinal control @@ -312,4 +351,13 @@ struct CarParams { stoppingControl @34 :Bool; # Does the car allows full control even at lows speeds when stopping startAccel @35 :Float32; # Required acceleraton to overcome creep braking steerRateCost @40 :Float32; # Lateral MPC cost on steering rate + steerControlType @46 :SteerControlType; + radarOffCan @47 :Bool; # True when radar objects aren't visible on CAN + + steerActuatorDelay @48 :Float32; # Steering wheel actuator delay in seconds + + enum SteerControlType { + torque @0; + angle @1; + } } diff --git a/cereal/c++.capnp b/cereal/include/c++.capnp similarity index 100% rename from cereal/c++.capnp rename to cereal/include/c++.capnp diff --git a/cereal/java.capnp b/cereal/include/java.capnp similarity index 100% rename from cereal/java.capnp rename to cereal/include/java.capnp diff --git a/cereal/log.capnp b/cereal/log.capnp index c3ddad9bd30dd2..389b550ad421ae 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -1,7 +1,7 @@ -using Cxx = import "c++.capnp"; +using Cxx = import "./include/c++.capnp"; $Cxx.namespace("cereal"); -using Java = import "java.capnp"; +using Java = import "./include/java.capnp"; $Java.package("ai.comma.openpilot.cereal"); $Java.outerClassname("Log"); @@ -21,6 +21,8 @@ struct Map(Key, Value) { struct InitData { kernelArgs @0 :List(Text); + kernelVersion @15 :Text; + gctx @1 :Text; dongleId @2 :Text; @@ -32,17 +34,21 @@ struct InitData { androidBuildInfo @5 :AndroidBuildInfo; androidSensors @6 :List(AndroidSensor); + androidProperties @16 :Map(Text, Text); chffrAndroidExtra @7 :ChffrAndroidExtra; + iosBuildInfo @14 :IosBuildInfo; pandaInfo @8 :PandaInfo; dirty @9 :Bool; passive @12 :Bool; + params @17 :Map(Text, Text); enum DeviceType { unknown @0; neo @1; chffrAndroid @2; + chffrIos @3; } struct AndroidBuildInfo { @@ -93,6 +99,13 @@ struct InitData { allCameraCharacteristics @0 :Map(Text, Text); } + struct IosBuildInfo { + appVersion @0 :Text; + appBuild @1 :UInt32; + osVersion @2 :Text; + deviceModel @3 :Text; + } + struct PandaInfo { hasPanda @0 :Bool; dongleId @1 :Text; @@ -108,6 +121,10 @@ struct FrameData { frameLength @3 :Int32; integLines @4 :Int32; globalGain @5 :Int32; + lensPos @11 :Int32; + lensSag @12 :Float32; + lensErr @13 :Float32; + lensTruePos @14 :Float32; image @6 :Data; frameType @7 :FrameType; @@ -170,6 +187,10 @@ struct SensorEventData { iOS @1; fiber @2; velodyne @3; # Velodyne IMU + # c3 sensors below + bno055 @4; + lsm6ds3 @5; + bmp280 @6; } } @@ -222,6 +243,7 @@ struct GpsLocationData { fusion @4; external @5; ublox @6; + trimble @7; } } @@ -245,11 +267,23 @@ struct ThermalData { freeSpace @7 :Float32; batteryPercent @8 :Int16; batteryStatus @9 :Text; + batteryCurrent @15 :Int32; + batteryVoltage @16 :Int32; usbOnline @12 :Bool; fanSpeed @10 :UInt16; started @11 :Bool; startedTs @13 :UInt64; + + thermalStatus @14 :ThermalStatus; + chargerDisabled @17 :Bool; + + enum ThermalStatus { + green @0; # all processes run + yellow @1; # critical processes run (kill uploader), engage still allowed + red @2; # no engage, will disengage + danger @3; # immediate process shutdown + } } struct HealthData { @@ -260,6 +294,7 @@ struct HealthData { controlsAllowed @3 :Bool; gasInterceptorDetected @4 :Bool; startedSignalDetected @5 :Bool; + isGreyPanda @6 :Bool; } struct LiveUI { @@ -300,17 +335,21 @@ struct Live20Data { aLeadK @9 :Float32; fcw @10 :Bool; status @11 :Bool; + aLeadTau @12 :Float32; } } struct LiveCalibrationData { + # deprecated warpMatrix @0 :List(Float32); + # camera_frame_from_model_frame warpMatrix2 @5 :List(Float32); calStatus @1 :Int8; calCycle @2 :Int32; calPerc @3 :Int8; - # Maps car space to normalized image space. + # view_frame_from_road_frame + # ui's is inversed needs new extrinsicMatrix @4 :List(Float32); } @@ -370,9 +409,14 @@ struct Live100Data { alertText2 @25 :Text; alertStatus @38 :AlertStatus; alertSize @39 :AlertSize; + alertBlinkingRate @42 :Float32; + alertType @44 :Text; + alertSound @45 :Text; awarenessStatus @26 :Float32; - angleOffset @27 :Float32; + gpsPlannerActive @40 :Bool; + engageable @41 :Bool; # can OP be engaged? + driverMonitoringOn @43 :Bool; enum ControlState { disabled @0; @@ -469,6 +513,7 @@ struct EncodeIndex { bigBoxHEVC @2; # bcamera.hevc chffrAndroidH264 @3; # acamera fullLosslessClip @4; # prcamera.mkv + front @5; # dcamera.hevc } } @@ -503,6 +548,7 @@ struct Plan { aCruise @17 :Float32; vTarget @3 :Float32; vTargetFuture @14 :Float32; + vMax @20 :Float32; aTargetMinDEPRECATED @4 :Float32; aTargetMaxDEPRECATED @5 :Float32; aTarget @18 :Float32; @@ -514,6 +560,8 @@ struct Plan { # gps trajectory in car frame gpsTrajectory @12 :GpsTrajectory; + gpsPlannerActive @19 :Bool; + struct GpsTrajectory { x @0 :List(Float32); y @1 :List(Float32); @@ -523,6 +571,7 @@ struct Plan { cruise @0; mpc1 @1; mpc2 @2; + mpc3 @3; } } @@ -559,6 +608,19 @@ struct LiveLocationData { accuracy @13 :Accuracy; + source @14 :SensorSource; + # if we are fixing a location in the past + fixMonoTime @15 :UInt64; + + gpsWeek @16 :Int32; + timeOfWeek @17 :Float64; + + positionECEF @18 :List(Float64); + poseQuatECEF @19 :List(Float32); + pitchCalibration @20 :Float32; + yawCalibration @21 :Float32; + imuFrame @22 :List(Float32); + struct Accuracy { pNEDError @0 :List(Float32); vNEDError @1 :List(Float32); @@ -569,6 +631,14 @@ struct LiveLocationData { ellipsoidSemiMinorError @6 :Float32; ellipsoidOrientationError @7 :Float32; } + + enum SensorSource { + applanix @0; + kalman @1; + orbslam @2; + timing @3; + dummy @4; + } } struct EthernetPacket { @@ -1252,6 +1322,11 @@ struct UbloxGnss { fitInterval @35 :Float64; toc @36 :Float64; + + ionoCoeffsValid @37 :Bool; + ionoAlpha @38 :List(Float64); + ionoBeta @39 :List(Float64); + } struct IonoData { @@ -1283,6 +1358,7 @@ struct LiveMpcData { delta @3 :List(Float32); qpIterations @4 :UInt32; calculationTime @5 :UInt64; + cost @6 :Float64; } struct LiveLongitudinalMpcData { @@ -1296,8 +1372,206 @@ struct LiveLongitudinalMpcData { qpIterations @7 :UInt32; mpcId @8 :UInt32; calculationTime @9 :UInt64; + cost @10 :Float64; +} + + +struct ECEFPointDEPRECATED @0xe10e21168db0c7f7 { + x @0 :Float32; + y @1 :Float32; + z @2 :Float32; +} + +struct ECEFPoint @0xc25bbbd524983447 { + x @0 :Float64; + y @1 :Float64; + z @2 :Float64; +} + +struct GPSPlannerPoints { + curPosDEPRECATED @0 :ECEFPointDEPRECATED; + pointsDEPRECATED @1 :List(ECEFPointDEPRECATED); + curPos @6 :ECEFPoint; + points @7 :List(ECEFPoint); + valid @2 :Bool; + trackName @3 :Text; + speedLimit @4 :Float32; + accelTarget @5 :Float32; +} + +struct GPSPlannerPlan { + valid @0 :Bool; + poly @1 :List(Float32); + trackName @2 :Text; + speed @3 :Float32; + acceleration @4 :Float32; + pointsDEPRECATED @5 :List(ECEFPointDEPRECATED); + points @6 :List(ECEFPoint); + xLookahead @7 :Float32; +} + +struct TrafficEvent @0xacfa74a094e62626 { + type @0 :Type; + distance @1 :Float32; + action @2 :Action; + resuming @3 :Bool; + + enum Type { + stopSign @0; + lightRed @1; + lightYellow @2; + lightGreen @3; + stopLight @4; + } + + enum Action { + none @0; + yield @1; + stop @2; + resumeReady @3; + } + +} + +struct OrbslamCorrection { + correctionMonoTime @0 :UInt64; + prePositionECEF @1 :List(Float64); + postPositionECEF @2 :List(Float64); + prePoseQuatECEF @3 :List(Float32); + postPoseQuatECEF @4 :List(Float32); + numInliers @5 :UInt32; +} + +struct OrbObservation { + observationMonoTime @0 :UInt64; + normalizedCoordinates @1 :List(Float32); + locationECEF @2 :List(Float64); + matchDistance @3: UInt32; } +struct UiNavigationEvent { + type @0: Type; + status @1: Status; + distanceTo @2: Float32; + endRoadPointDEPRECATED @3: ECEFPointDEPRECATED; + endRoadPoint @4: ECEFPoint; + + enum Type { + none @0; + laneChangeLeft @1; + laneChangeRight @2; + mergeLeft @3; + mergeRight @4; + turnLeft @5; + turnRight @6; + } + + enum Status { + none @0; + passive @1; + approaching @2; + active @3; + } +} + +struct UiLayoutState { + activeApp @0 :App; + sidebarCollapsed @1 :Bool; + mapEnabled @2 :Bool; + + enum App { + home @0; + music @1; + nav @2; + } +} + +struct Joystick { + # convenient for debug and live tuning + axes @0: List(Float32); + buttons @1: List(Bool); +} + +struct OrbOdometry { + # timing first + startMonoTime @0 :UInt64; + endMonoTime @1 :UInt64; + + # fundamental matrix and error + f @2: List(Float64); + err @3: Float64; + + # number of inlier points + inliers @4: Int32; + + # for debug only + # indexed by endMonoTime features + # value is startMonoTime feature match + # -1 if no match + matches @5: List(Int16); +} + +struct OrbFeatures { + timestampEof @0 :UInt64; + # transposed arrays of normalized image coordinates + # len(xs) == len(ys) == len(descriptors) * 32 + xs @1 :List(Float32); + ys @2 :List(Float32); + descriptors @3 :Data; + octaves @4 :List(Int8); + + # match index to last OrbFeatures + # -1 if no match + timestampLastEof @5 :UInt64; + matches @6: List(Int16); +} + +struct OrbFeaturesSummary { + timestampEof @0 :UInt64; + timestampLastEof @1 :UInt64; + + featureCount @2 :UInt16; + matchCount @3 :UInt16; + computeNs @4 :UInt64; +} + +struct OrbKeyFrame { + # this is a globally unique id for the KeyFrame + id @0: UInt64; + + # this is the location of the KeyFrame + pos @1: ECEFPoint; + + # these are the features in the world + # len(dpos) == len(descriptors) * 32 + dpos @2 :List(ECEFPoint); + descriptors @3 :Data; +} + +struct DriverMonitoring { + frameId @0 :UInt32; + descriptor @1 :List(Float32); + std @2 :Float32; +} + +struct Boot { + wallTimeNanos @0 :UInt64; + lastKmsg @1 :Data; + lastPmsg @2 :Data; +} + +struct LiveParametersData { + valid @0 :Bool; + gyroBias @1 :Float32; + angleOffset @2 :Float32; +} + +struct LiveMapData { + valid @0 :Bool; + speedLimit @1 :Float32; +} + + struct Event { # in nanoseconds? logMonoTime @0 :UInt64; @@ -1341,5 +1615,29 @@ struct Event { liveMpc @36 :LiveMpcData; liveLongitudinalMpc @37 :LiveLongitudinalMpcData; navStatus @38 :NavStatus; + ubloxRaw @39 :Data; + gpsPlannerPoints @40 :GPSPlannerPoints; + gpsPlannerPlan @41 :GPSPlannerPlan; + applanixRaw @42 :Data; + trafficEvents @43 :List(TrafficEvent); + liveLocationTiming @44 :LiveLocationData; + orbslamCorrectionDEPRECATED @45 :OrbslamCorrection; + liveLocationCorrected @46 :LiveLocationData; + orbObservation @47 :List(OrbObservation); + gpsLocationExternal @48 :GpsLocationData; + location @49 :LiveLocationData; + uiNavigationEvent @50 :UiNavigationEvent; + liveLocationKalman @51 :LiveLocationData; + testJoystick @52 :Joystick; + orbOdometry @53 :OrbOdometry; + orbFeatures @54 :OrbFeatures; + applanixLocation @55 :LiveLocationData; + orbKeyFrame @56 :OrbKeyFrame; + uiLayoutState @57 :UiLayoutState; + orbFeaturesSummary @58 :OrbFeaturesSummary; + driverMonitoring @59 :DriverMonitoring; + boot @60 :Boot; + liveParameters @61 :LiveParametersData; + liveMapData @62 :LiveMapData; } } diff --git a/common/dbc.py b/common/dbc.py index 8865ae0f582611..6accad43f82bec 100755 --- a/common/dbc.py +++ b/common/dbc.py @@ -1,8 +1,9 @@ import re import os import struct -import bitstring -from collections import namedtuple +import sys +import numbers +from collections import namedtuple, defaultdict def int_or_float(s): # return number, trying to maintain int format @@ -15,6 +16,7 @@ def int_or_float(s): "DBCSignal", ["name", "start_bit", "size", "is_little_endian", "is_signed", "factor", "offset", "tmin", "tmax", "units"]) + class dbc(object): def __init__(self, fn): self.name, _ = os.path.splitext(os.path.basename(fn)) @@ -23,9 +25,10 @@ def __init__(self, fn): self._warned_addresses = set() # regexps from https://github.com/ebroecker/canmatrix/blob/master/canmatrix/importdbc.py - bo_regexp = re.compile("^BO\_ (\w+) (\w+) *: (\w+) (\w+)") - sg_regexp = re.compile("^SG\_ (\w+) : (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") - sgm_regexp = re.compile("^SG\_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + bo_regexp = re.compile(r"^BO\_ (\w+) (\w+) *: (\w+) (\w+)") + sg_regexp = re.compile(r"^SG\_ (\w+) : (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + sgm_regexp = re.compile(r"^SG\_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + val_regexp = re.compile(r"VAL\_ (\w+) (\w+) (\s*[-+]?[0-9]+\s+\".+?\"[^;]*)") # A dictionary which maps message ids to tuples ((name, size), signals). # name is the ASCII name of the message. @@ -34,6 +37,9 @@ def __init__(self, fn): # signals is a list of DBCSignal in order of increasing start_bit. self.msgs = {} + # A dictionary which maps message ids to a list of tuples (signal name, definition value pairs) + self.def_vals = defaultdict(list) + # lookup to bit reverse each byte self.bits_index = [(i & ~0b111) + ((-i-1) & 0b111) for i in xrange(64)] @@ -49,6 +55,8 @@ def __init__(self, fn): name = dat.group(2) size = int(dat.group(3)) ids = int(dat.group(1), 0) # could be hex + if ids in self.msgs: + sys.exit("Duplicate address detected %d %s" % (ids, self.name)) self.msgs[ids] = ((name, size), []) @@ -77,9 +85,53 @@ def __init__(self, fn): DBCSignal(sgname, start_bit, signal_size, is_little_endian, is_signed, factor, offset, tmin, tmax, units)) + if l.startswith("VAL_ "): + # new signal value/definition + dat = val_regexp.match(l) + + if dat is None: + print "bad VAL", l + ids = int(dat.group(1), 0) # could be hex + sgname = dat.group(2) + defvals = dat.group(3) + + defvals = defvals.replace("?","\?") #escape sequence in C++ + defvals = defvals.split('"')[:-1] + + defs = defvals[1::2] + #cleanup, convert to UPPER_CASE_WITH_UNDERSCORES + for i,d in enumerate(defs): + d = defs[i].strip().upper() + defs[i] = d.replace(" ","_") + + defvals[1::2] = defs + defvals = '"'+"".join(str(i) for i in defvals)+'"' + + self.def_vals[ids].append((sgname, defvals)) + for msg in self.msgs.viewvalues(): msg[1].sort(key=lambda x: x.start_bit) + self.msg_name_to_address = {} + for address, m in self.msgs.items(): + name = m[0][0] + self.msg_name_to_address[name] = address + + def lookup_msg_id(self, msg_id): + if not isinstance(msg_id, numbers.Number): + msg_id = self.msg_name_to_address[msg_id] + return msg_id + + def reverse_bytes(self, x): + return ((x & 0xff00000000000000) >> 56) | \ + ((x & 0x00ff000000000000) >> 40) | \ + ((x & 0x0000ff0000000000) >> 24) | \ + ((x & 0x000000ff00000000) >> 8) | \ + ((x & 0x00000000ff000000) << 8) | \ + ((x & 0x0000000000ff0000) << 24) | \ + ((x & 0x000000000000ff00) << 40) | \ + ((x & 0x00000000000000ff) << 56) + def encode(self, msg_id, dd): """Encode a CAN message using the dbc. @@ -87,35 +139,42 @@ def encode(self, msg_id, dd): msg_id: The message ID. dd: A dictionary mapping signal name to signal data. """ - # TODO: Stop using bitstring, which is super slow. + msg_id = self.lookup_msg_id(msg_id) + msg_def = self.msgs[msg_id] size = msg_def[0][1] - bsf = bitstring.Bits(hex="00"*size) + result = 0 for s in msg_def[1]: ival = dd.get(s.name) if ival is not None: - ival = (ival / s.factor) - s.offset - ival = int(round(ival)) - # should pack this + b2 = s.size if s.is_little_endian: - ss = s.start_bit + b1 = s.start_bit else: - ss = self.bits_index[s.start_bit] + b1 = (s.start_bit // 8) * 8 + (-s.start_bit - 1) % 8 + bo = 64 - (b1 + s.size) + ival = (ival / s.factor) - s.offset + ival = int(round(ival)) - if s.is_signed: - tbs = bitstring.Bits(int=ival, length=s.size) - else: - tbs = bitstring.Bits(uint=ival, length=s.size) + if s.is_signed and ival < 0: + ival = (1 << b2) + ival + + shift = b1 if s.is_little_endian else bo + mask = ((1 << b2) - 1) << shift + dat = (ival & ((1 << b2) - 1)) << shift - lpad = bitstring.Bits(bin="0b"+"0"*ss) - rpad = bitstring.Bits(bin="0b"+"0"*(8*size-(ss+s.size))) - tbs = lpad+tbs+rpad + if s.is_little_endian: + mask = self.reverse_bytes(mask) + dat = self.reverse_bytes(dat) + + result &= ~mask + result |= dat - bsf |= tbs - return bsf.tobytes() + result = struct.pack('>Q', result) + return result[:size] def decode(self, x, arr=None, debug=False): """Decode a CAN message using the dbc. @@ -134,7 +193,7 @@ def decode(self, x, arr=None, debug=False): Returns (None, None) if the message could not be decoded. """ - + if arr is None: out = {} else: @@ -151,56 +210,77 @@ def decode(self, x, arr=None, debug=False): if debug: print name - blen = 8*len(x[2]) - - st = x[2].rjust(8, '\x00') + st = x[2].ljust(8, '\x00') le, be = None, None for s in msg[1]: if arr is not None and s[0] not in arr: continue - # big or little endian? - # see http://vi-firmware.openxcplatform.com/en/master/config/bit-numbering.html - if s[3] is False: - ss = self.bits_index[s[1]] - if be is None: - be = struct.unpack(">Q", st)[0] - x2_int = be - data_bit_pos = (blen - (ss + s[2])) + start_bit = s[1] + signal_size = s[2] + little_endian = s[3] + signed = s[4] + factor = s[5] + offset = s[6] + + b2 = signal_size + if little_endian: + b1 = start_bit else: + b1 = (start_bit // 8) * 8 + (-start_bit - 1) % 8 + bo = 64 - (b1 + signal_size) + + if little_endian: if le is None: le = struct.unpack("Q", st)[0] + shift_amount = bo + tmp = be - if data_bit_pos < 0: + if shift_amount < 0: continue - ival = (x2_int >> data_bit_pos) & ((1 << (s[2])) - 1) - if s[4] and (ival & (1<<(s[2]-1))): # signed - ival -= (1<> shift_amount) & ((1 << b2) - 1) + if signed and (tmp >> (b2 - 1)): + tmp -= (1 << b2) + + tmp = tmp * factor + offset - # control the offset - ival = (ival * s[5]) + s[6] - #if debug: - # print "%40s %2d %2d %7.2f %s" % (s[0], s[1], s[2], ival, s[-1]) + # if debug: + # print "%40s %2d %2d %7.2f %s" % (s[0], s[1], s[2], tmp, s[-1]) if arr is None: - out[s[0]] = ival + out[s[0]] = tmp else: - out[arr.index(s[0])] = ival + out[arr.index(s[0])] = tmp return name, out - def get_signals(self, msg): + msg = self.lookup_msg_id(msg) return [sgs.name for sgs in self.msgs[msg][1]] - + + if __name__ == "__main__": - import sys - import os from opendbc import DBC_PATH + import numpy as np + + dbc_test = dbc(os.path.join(DBC_PATH, 'toyota_prius_2017_pt_generated.dbc')) + msg = ('STEER_ANGLE_SENSOR', {'STEER_ANGLE': -6.0, 'STEER_RATE': 4, 'STEER_FRACTION': -0.2}) + encoded = dbc_test.encode(*msg) + decoded = dbc_test.decode((0x25, 0, encoded)) + assert decoded == msg + + dbc_test = dbc(os.path.join(DBC_PATH, 'hyundai_santa_fe_2019_ccan.dbc')) + decoded = dbc_test.decode((0x2b0, 0, "\xfa\xfe\x00\x07\x12")) + assert np.isclose(decoded[1]['SAS_Angle'], -26.2) + + msg = ('SAS11', {'SAS_Stat': 7.0, 'MsgCount': 0.0, 'SAS_Angle': -26.200000000000003, 'SAS_Speed': 0.0, 'CheckSum': 0.0}) + encoded = dbc_test.encode(*msg) + decoded = dbc_test.decode((0x2b0, 0, encoded)) - dbc_test = dbc(os.path.join(DBC_PATH, sys.argv[1])) - print dbc_test.get_signals(0xe4) + assert decoded == msg diff --git a/common/ffi_wrapper.py b/common/ffi_wrapper.py new file mode 100644 index 00000000000000..65b790a803469e --- /dev/null +++ b/common/ffi_wrapper.py @@ -0,0 +1,42 @@ +import os +import sys +import fcntl +import hashlib +from cffi import FFI + +TMPDIR = "/tmp/ccache" + +def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=[]): + cache = name + "_" + hashlib.sha1(c_code).hexdigest() + try: + os.mkdir(tmpdir) + except OSError: + pass + + fd = os.open(tmpdir, 0) + fcntl.flock(fd, fcntl.LOCK_EX) + try: + sys.path.append(tmpdir) + try: + mod = __import__(cache) + except Exception: + print "cache miss", cache + compile_code(cache, c_code, c_header, tmpdir, cflags, libraries) + mod = __import__(cache) + finally: + os.close(fd) + + return mod.ffi, mod.lib + +def compile_code(name, c_code, c_header, directory, cflags="", libraries=[]): + ffibuilder = FFI() + ffibuilder.set_source(name, c_code, source_extension='.cpp', libraries=libraries) + ffibuilder.cdef(c_header) + os.environ['OPT'] = "-fwrapv -O2 -DNDEBUG -std=c++11" + os.environ['CFLAGS'] = cflags + ffibuilder.compile(verbose=True, debug=False, tmpdir=directory) + +def wrap_compiled(name, directory): + sys.path.append(directory) + mod = __import__(name) + return mod.ffi, mod.lib diff --git a/common/filter_simple.py b/common/filter_simple.py new file mode 100644 index 00000000000000..a3206db1cc5684 --- /dev/null +++ b/common/filter_simple.py @@ -0,0 +1,10 @@ +class FirstOrderFilter(): + # first order filter + def __init__(self, x0, ts, dt): + self.k = (dt / ts) / (1. + dt / ts) + self.x = x0 + + def update(self, x): + self.x = (1. - self.k) * self.x + self.k * x + + diff --git a/common/fingerprints.py b/common/fingerprints.py index d5b9cc91d0db60..d4845f8d416a0a 100644 --- a/common/fingerprints.py +++ b/common/fingerprints.py @@ -1,38 +1,38 @@ import os +from common.basedir import BASEDIR + +def get_fingerprint_list(): + # read all the folders in selfdrive/car and return a dict where: + # - keys are all the car models for which we have a fingerprint + # - values are lists dicts of messages that constitute the unique + # CAN fingerprint of each car model and all its variants + fingerprints = {} + for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: + try: + car_name = car_folder.split('/')[-1] + values = __import__('selfdrive.car.%s.values' % car_name, fromlist=['FINGERPRINTS']) + if hasattr(values, 'FINGERPRINTS'): + car_fingerprints = values.FINGERPRINTS + else: + continue + for f, v in car_fingerprints.items(): + fingerprints[f] = v + except (ImportError, IOError): + pass + return fingerprints + + +_FINGERPRINTS = get_fingerprint_list() + +_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes + +def is_valid_for_fingerprint(msg, car_fingerprint): + adr = msg.address + bus = msg.src + # ignore addresses that are more than 11 bits + return (adr in car_fingerprint and car_fingerprint[adr] == len(msg.dat)) or \ + bus != 0 or adr >= 0x800 -_FINGERPRINTS = { - "ACURA ILX 2016 ACURAWATCH PLUS": { - 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 929L: 4, 1057L: 5, 777L: 8, 1034L: 5, 1036L: 8, 398L: 3, 399L: 7, 145L: 8, 660L: 8, 985L: 3, 923L: 2, 542L: 7, 773L: 7, 800L: 8, 432L: 7, 419L: 8, 420L: 8, 1030L: 5, 422L: 8, 808L: 8, 428L: 8, 304L: 8, 819L: 7, 821L: 5, 57L: 3, 316L: 8, 545L: 4, 464L: 8, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 344L: 8, 804L: 8, 1039L: 8, 476L: 4, 892L: 8, 490L: 8, 1064L: 7, 882L: 2, 884L: 7, 887L: 8, 888L: 8, 380L: 8, 1365L: 5, - # sent messages - 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5, - }, - "HONDA CIVIC 2016 TOURING": { - 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 777L: 8, 1036L: 8, 1039L: 8, 1424L: 5, 401L: 8, 148L: 8, 662L: 4, 985L: 3, 795L: 8, 773L: 7, 800L: 8, 545L: 6, 420L: 8, 806L: 8, 808L: 8, 1322L: 5, 427L: 3, 428L: 8, 304L: 8, 432L: 7, 57L: 3, 450L: 8, 929L: 8, 330L: 8, 1302L: 8, 464L: 8, 1361L: 5, 1108L: 8, 597L: 8, 470L: 2, 344L: 8, 804L: 8, 399L: 7, 476L: 7, 1633L: 8, 487L: 4, 892L: 8, 490L: 8, 493L: 5, 884L: 8, 891L: 8, 380L: 8, 1365L: 5, - # sent messages - 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5, 0x35e: 8, 0x39f: 8, - }, - "HONDA CR-V 2016 TOURING": { - 57L: 3, 145L: 8, 316L: 8, 340L: 8, 342L: 6, 344L: 8, 380L: 8, 398L: 3, 399L: 6, 401L: 8, 420L: 8, 422L: 8, 426L: 8, 432L: 7, 464L: 8, 474L: 5, 476L: 4, 487L: 4, 490L: 8, 493L: 3, 507L: 1, 542L: 7, 545L: 4, 597L: 8, 660L: 8, 661L: 4, 773L: 7, 777L: 8, 800L: 8, 804L: 8, 808L: 8, 882L: 2, 884L: 7, 888L: 8, 891L: 8, 892L: 8, 923L: 2, 929L: 8, 983L: 8, 985L: 3, 1024L: 5, 1027L: 5, 1029L: 8, 1033L: 5, 1036L: 8, 1039L: 8, 1057L: 5, 1064L: 7, 1108L: 8, 1125L: 8, 1296L: 8, 1365L: 5, 1424L: 5, 1600L: 5, 1601L: 8, - # sent messages - 0x194: 4, 0x1fa: 8, 0x30c: 8, 0x33d: 5, - }, - "TOYOTA RAV4 2017": { - 36L: 8, 37L: 8, 170L: 8, 180L: 8, 186L: 4, 426L: 6, 452L: 8, 464L: 8, 466L: 8, 467L: 8, 547L: 8, 548L: 8, 552L: 4, 562L: 4, 608L: 8, 610L: 5, 643L: 7, 705L: 8, 725L: 2, 740L: 5, 800L: 8, 835L: 8, 836L: 8, 849L: 4, 869L: 7, 870L: 7, 871L: 2, 896L: 8, 897L: 8, 900L: 6, 902L: 6, 905L: 8, 911L: 8, 916L: 3, 918L: 7, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 951L: 8, 955L: 4, 956L: 8, 979L: 2, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1008L: 2, 1014L: 8, 1017L: 8, 1041L: 8, 1042L: 8, 1043L: 8, 1044L: 8, 1056L: 8, 1059L: 1, 1114L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1176L: 8, 1177L: 8, 1178L: 8, 1179L: 8, 1180L: 8, 1181L: 8, 1190L: 8, 1191L: 8, 1192L: 8, 1196L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1263L: 8, 1279L: 8, 1408L: 8, 1409L: 8, 1410L: 8, 1552L: 8, 1553L: 8, 1554L: 8, 1555L: 8, 1556L: 8, 1557L: 8, 1561L: 8, 1562L: 8, 1568L: 8, 1569L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1584L: 8, 1589L: 8, 1592L: 8, 1593L: 8, 1595L: 8, 1596L: 8, 1597L: 8, 1600L: 8, 1656L: 8, 1664L: 8, 1728L: 8, 1745L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8 - }, - "TOYOTA RAV4 2017 HYBRID": { - 36L: 8, 37L: 8, 170L: 8, 180L: 8, 296L: 8, 426L: 6, 452L: 8, 466L: 8, 467L: 8, 550L: 8, 552L: 4, 560L: 7, 581L: 5, 608L: 8, 610L: 5, 643L: 7, 713L: 8, 740L: 5, 800L: 8, 835L: 8, 836L: 8, 849L: 4, 869L: 7, 870L: 7, 871L: 2, 896L: 8, 897L: 8, 900L: 6, 902L: 6, 905L: 8, 911L: 8, 916L: 3, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 950L: 8, 951L: 8, 953L: 3, 955L: 8, 956L: 8, 979L: 2, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1005L: 2, 1017L: 8, 1041L: 8, 1042L: 8, 1043L: 8, 1044L: 8, 1056L: 8, 1059L: 1, 1114L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1176L: 8, 1177L: 8, 1178L: 8, 1179L: 8, 1180L: 8, 1181L: 8, 1184L: 8, 1185L: 8, 1186L: 8, 1190L: 8, 1191L: 8, 1192L: 8, 1196L: 8, 1197L: 8, 1198L: 8, 1199L: 8, 1212L: 8, 1227L: 8, 1232L: 8, 1235L: 8, 1264L: 8, 1279L: 8, 1408L: 8, 1409L: 8, 1410L: 8, 1552L: 8, 1553L: 8, 1554L: 8, 1555L: 8, 1556L: 8, 1557L: 8, 1561L: 8, 1562L: 8, 1568L: 8, 1569L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1584L: 8, 1589L: 8, 1592L: 8, 1596L: 8, 1597L: 8, 1600L: 8, 1664L: 8, 1728L: 8, 1745L: 8, 1779L: 8 - }, - "TOYOTA PRIUS 2017": { - 36L: 8, 37L: 8, 166L: 8, 170L: 8, 180L: 8, 295L: 8, 296L: 8, 426L: 6, 452L: 8, 466L: 8, 467L: 8, 550L: 8, 552L: 4, 560L: 7, 562L: 6, 581L: 5, 608L: 8, 610L: 8, 614L: 8, 643L: 7, 658L: 8, 713L: 8, 740L: 5, 742L: 8, 743L: 8, 800L: 8, 810L: 2, 814L: 8, 829L: 2, 830L: 7, 835L: 8, 836L: 8, 863L: 8, 869L: 7, 870L: 7, 871L: 2, 898L: 8, 900L: 6, 902L: 6, 905L: 8, 918L: 8, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 950L: 8, 951L: 8, 953L: 8, 955L: 8, 956L: 8, 971L: 7, 975L: 5, 993L: 8, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1014L: 8, 1017L: 8, 1020L: 8, 1041L: 8, 1042L: 8, 1044L: 8, 1056L: 8, 1057L: 8, 1059L: 1, 1071L: 8, 1077L: 8, 1082L: 8, 1083L: 8, 1084L: 8, 1085L: 8, 1086L: 8, 1114L: 8, 1132L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1175L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1279L: 8, 1552L: 8, 1553L: 8, 1556L: 8, 1557L: 8, 1568L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1595L: 8, 1777L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8 - }, -} - -# support additional internal only fingerprints -try: - from common.fingerprints_internal import add_additional_fingerprints - add_additional_fingerprints(_FINGERPRINTS) -except ImportError: - pass def eliminate_incompatible_cars(msg, candidate_cars): """Removes cars that could not have sent msg. @@ -45,18 +45,20 @@ def eliminate_incompatible_cars(msg, candidate_cars): A list containing the subset of candidate_cars that could have sent msg. """ compatible_cars = [] + for car_name in candidate_cars: - adr = msg.address - if msg.src != 0 or (adr in _FINGERPRINTS[car_name] and - _FINGERPRINTS[car_name][adr] == len(msg.dat)): - compatible_cars.append(car_name) - else: - pass - #isin = adr in _FINGERPRINTS[car_name] - #print "eliminate", car_name, hex(adr), isin, len(msg.dat), msg.dat.encode("hex") + car_fingerprints = _FINGERPRINTS[car_name] + + for fingerprint in car_fingerprints: + fingerprint.update(_DEBUG_ADDRESS) # add alien debug address + + if is_valid_for_fingerprint(msg, fingerprint): + compatible_cars.append(car_name) + break + return compatible_cars + def all_known_cars(): """Returns a list of all known car strings.""" return _FINGERPRINTS.keys() - diff --git a/common/kalman/ekf.py b/common/kalman/ekf.py index feebe0883f1070..fbed218f7a7b38 100644 --- a/common/kalman/ekf.py +++ b/common/kalman/ekf.py @@ -1,6 +1,7 @@ +# pylint: skip-file +from __future__ import print_function import abc import numpy as np -import numpy.matlib # The EKF class contains the framework for an Extended Kalman Filter, but must be subclassed to use. # A subclass must implement: # 1) calc_transfer_fun(); see bottom of file for more info. @@ -92,8 +93,8 @@ def update(self, reading): innovation = reading.data - reading.obs_model * self.state if self.DEBUG: - print "reading:\n",reading.data - print "innovation:\n",innovation + print("reading:\n",reading.data) + print("innovation:\n",innovation) # S = H*P*H' + R innovation_covar = reading.obs_model * self.covar * reading.obs_model.T + reading.covar @@ -103,12 +104,12 @@ def update(self, reading): innovation_covar) if self.DEBUG: - print "gain:\n", kalman_gain - print "innovation_covar:\n", innovation_covar - print "innovation: ", innovation - print "test: ", self.covar * reading.obs_model.T * ( + print("gain:\n", kalman_gain) + print("innovation_covar:\n", innovation_covar) + print("innovation: ", innovation) + print("test: ", self.covar * reading.obs_model.T * ( reading.obs_model * self.covar * reading.obs_model.T + reading.covar * - 0).I + 0).I) # x = x + K*y self.state += kalman_gain*innovation @@ -124,9 +125,9 @@ def update(self, reading): self.covar = aux_mtrx * self.covar * aux_mtrx.T + kalman_gain * reading.covar * kalman_gain.T if self.DEBUG: - print "After update" - print "state\n", self.state - print "covar:\n",self.covar + print("After update") + print("state\n", self.state) + print("covar:\n",self.covar) def update_scalar(self, reading): # like update but knowing that measurement is a scalar diff --git a/common/logging_extra.py b/common/logging_extra.py index 359b3e09146b1c..43ae48882b956e 100644 --- a/common/logging_extra.py +++ b/common/logging_extra.py @@ -18,7 +18,7 @@ def json_robust_dumps(obj): class NiceOrderedDict(OrderedDict): def __str__(self): - return '{'+', '.join("%r: %r" % p for p in self.iteritems())+'}' + return json_robust_dumps(self) class SwagFormatter(logging.Formatter): def __init__(self, swaglogger): @@ -62,6 +62,10 @@ def format_dict(self, record): def format(self, record): return json_robust_dumps(self.format_dict(record)) +class SwagErrorFilter(logging.Filter): + def filter(self, record): + return record.levelno < logging.ERROR + _tmpfunc = lambda: 0 _srcfile = os.path.normcase(_tmpfunc.__code__.co_filename) @@ -74,7 +78,7 @@ def __init__(self): self.log_local = local() self.log_local.ctx = {} - def findCaller(self): + def findCaller(self, stack_info=None): """ Find the stack frame of the caller so that we can note the source file name, line number and function name. @@ -128,15 +132,43 @@ def event(self, event_name, *args, **kwargs): if args: evt['args'] = args evt.update(kwargs) - self.info(evt) + ctx = self.get_ctx() + if ctx: + evt['ctx'] = self.get_ctx() + if 'error' in kwargs: + self.error(evt) + else: + self.info(evt) if __name__ == "__main__": log = SwagLogger() + stdout_handler = logging.StreamHandler(sys.stdout) + stdout_handler.setLevel(logging.INFO) + stdout_handler.addFilter(SwagErrorFilter()) + log.addHandler(stdout_handler) + + stderr_handler = logging.StreamHandler(sys.stderr) + stderr_handler.setLevel(logging.ERROR) + log.addHandler(stderr_handler) + log.info("asdasd %s", "a") log.info({'wut': 1}) + log.warning("warning") + log.error("error") + log.critical("critical") + log.event("test", x="y") with log.ctx(): + stdout_handler.setFormatter(SwagFormatter(log)) + stderr_handler.setFormatter(SwagFormatter(log)) log.bind(user="some user") log.info("in req") - log.event("do_req") + print("") + log.warning("warning") + print("") + log.error("error") + print("") + log.critical("critical") + print("") + log.event("do_req", a=1, b="c") diff --git a/common/numpy_fast.py b/common/numpy_fast.py index 646a8bb1ab37de..eb706a908ff643 100644 --- a/common/numpy_fast.py +++ b/common/numpy_fast.py @@ -1,25 +1,18 @@ +def int_rnd(x): + return int(round(x)) + def clip(x, lo, hi): return max(lo, min(hi, x)) - def interp(x, xp, fp): N = len(xp) - if not hasattr(x, '__iter__'): - hi = 0 - while hi < N and x > xp[hi]: - hi += 1 - low = hi - 1 - return fp[-1] if hi == N and x > xp[low] else ( - fp[0] if hi == 0 else - (x - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low]) + fp[low]) - - result = [] - for v in x: + def get_interp(xv): hi = 0 - while hi < N and v > xp[hi]: + while hi < N and xv > xp[hi]: hi += 1 low = hi - 1 - result.append(fp[-1] if hi == N and v > xp[low] else (fp[ - 0] if hi == 0 else (v - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low] - ) + fp[low])) - return result + return fp[-1] if hi == N and xv > xp[low] else ( + fp[0] if hi == 0 else + (xv - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low]) + fp[low]) + return [get_interp(v) for v in x] if hasattr( + x, '__iter__') else get_interp(x) diff --git a/common/params.py b/common/params.py index d6503291eb4e4d..3981a341f4e28c 100755 --- a/common/params.py +++ b/common/params.py @@ -37,7 +37,7 @@ def mkdirs_exists_ok(path): raise class TxType(Enum): - PERSISTANT = 1 + PERSISTENT = 1 CLEAR_ON_MANAGER_START = 2 CLEAR_ON_CAR_START = 3 @@ -46,32 +46,36 @@ class UnknownKeyName(Exception): keys = { # written: manager -# read: loggerd, uploaderd, baseui - "DongleId": TxType.PERSISTANT, - "AccessToken": TxType.PERSISTANT, - "Version": TxType.PERSISTANT, - "GitCommit": TxType.PERSISTANT, - "GitBranch": TxType.PERSISTANT, - "GitRemote": TxType.PERSISTANT, +# read: loggerd, uploaderd, offroad + "DongleId": TxType.PERSISTENT, + "AccessToken": TxType.PERSISTENT, + "Version": TxType.PERSISTENT, + "TrainingVersion": TxType.PERSISTENT, + "GitCommit": TxType.PERSISTENT, + "GitBranch": TxType.PERSISTENT, + "GitRemote": TxType.PERSISTENT, # written: baseui # read: ui, controls - "IsMetric": TxType.PERSISTANT, - "IsRearViewMirror": TxType.PERSISTANT, - "IsFcwEnabled": TxType.PERSISTANT, - "HasAcceptedTerms": TxType.PERSISTANT, - "IsUploadVideoOverCellularEnabled": TxType.PERSISTANT, + "IsMetric": TxType.PERSISTENT, + "IsFcwEnabled": TxType.PERSISTENT, + "HasAcceptedTerms": TxType.PERSISTENT, + "CompletedTrainingVersion": TxType.PERSISTENT, + "IsUploadVideoOverCellularEnabled": TxType.PERSISTENT, + "IsDriverMonitoringEnabled": TxType.PERSISTENT, + "IsGeofenceEnabled": TxType.PERSISTENT, # written: visiond # read: visiond, controlsd - "CalibrationParams": TxType.PERSISTANT, -# written: visiond -# read: visiond, ui - "CloudCalibration": TxType.PERSISTANT, + "CalibrationParams": TxType.PERSISTENT, # written: controlsd # read: radard "CarParams": TxType.CLEAR_ON_CAR_START, - "Passive": TxType.PERSISTANT, + "Passive": TxType.PERSISTENT, "DoUninstall": TxType.CLEAR_ON_MANAGER_START, + "ShouldDoUpdate": TxType.CLEAR_ON_MANAGER_START, + "IsUpdateAvailable": TxType.PERSISTENT, + + "RecordFront": TxType.PERSISTENT, } def fsync_dir(path): @@ -227,7 +231,7 @@ def __exit__(self, type, value, traceback): data_path = self._data_path() try: old_data_path = os.path.join(self._path, os.readlink(data_path)) - except (OSError, IOError) as e: + except (OSError, IOError): # NOTE(mgraczyk): If other DB implementations have bugs, this could cause # copies to be left behind, but we still want to overwrite. pass @@ -259,23 +263,50 @@ def __exit__(self, type, value, traceback): self._lock = None +def read_db(params_path, key): + path = "%s/d/%s" % (params_path, key) + try: + with open(path, "rb") as f: + return f.read() + except IOError: + return None -class JSDB(object): - def __init__(self, fn): - self._fn = fn +def write_db(params_path, key, value): + prev_umask = os.umask(0) + lock = FileLock(params_path+"/.lock", True) + lock.acquire() - def begin(self, write=False): - if write: - return DBWriter(self._fn) - else: - return DBReader(self._fn) + try: + tmp_path = tempfile.mktemp(prefix=".tmp", dir=params_path) + with open(tmp_path, "wb") as f: + f.write(value) + f.flush() + os.fsync(f.fileno()) + + path = "%s/d/%s" % (params_path, key) + os.rename(tmp_path, path) + fsync_dir(os.path.dirname(path)) + finally: + os.umask(prev_umask) + lock.release() class Params(object): def __init__(self, db='/data/params'): - self.env = JSDB(db) + self.db = db + + # create the database if it doesn't exist... + if not os.path.exists(self.db+"/d"): + with self.transaction(write=True): + pass + + def transaction(self, write=False): + if write: + return DBWriter(self.db) + else: + return DBReader(self.db) def _clear_keys_with_type(self, tx_type): - with self.env.begin(write=True) as txn: + with self.transaction(write=True) as txn: for key in keys: if keys[key] == tx_type: txn.delete(key) @@ -287,7 +318,7 @@ def car_start(self): self._clear_keys_with_type(TxType.CLEAR_ON_CAR_START) def delete(self, key): - with self.env.begin(write=True) as txn: + with self.transaction(write=True) as txn: txn.delete(key) def get(self, key, block=False): @@ -295,8 +326,7 @@ def get(self, key, block=False): raise UnknownKeyName(key) while 1: - with self.env.begin() as txn: - ret = txn.get(key) + ret = read_db(self.db, key) if not block or ret is not None: break # is polling really the best we can do? @@ -307,9 +337,7 @@ def put(self, key, dat): if key not in keys: raise UnknownKeyName(key) - with self.env.begin(write=True) as txn: - txn.put(key, dat) - print "set", key + write_db(self.db, key, dat) if __name__ == "__main__": params = Params() @@ -319,11 +347,11 @@ def put(self, key, dat): for k in keys: pp = params.get(k) if pp is None: - print k, "is None" + print("%s is None" % k) elif all(ord(c) < 128 and ord(c) >= 32 for c in pp): - print k, pp + print("%s = %s" % (k, pp)) else: - print k, pp.encode("hex") + print("%s = %s" % (k, pp.encode("hex"))) # Test multiprocess: # seq 0 100000 | xargs -P20 -I{} python common/params.py DongleId {} && sleep 0.05 diff --git a/common/profiler.py b/common/profiler.py index 83e5672e0411de..7f9b1a41ffb188 100644 --- a/common/profiler.py +++ b/common/profiler.py @@ -6,7 +6,7 @@ def __init__(self, enabled=False): self.cp = {} self.cp_ignored = [] self.iter = 0 - self.start_time = time.clock() + self.start_time = time.time() self.last_time = self.start_time self.tot = 0. @@ -15,14 +15,14 @@ def reset(self, enabled=False): self.cp = {} self.cp_ignored = [] self.iter = 0 - self.start_time = time.clock() + self.start_time = time.time() self.last_time = self.start_time def checkpoint(self, name, ignore=False): # ignore flag needed when benchmarking threads with ratekeeper if not self.enabled: return - tt = time.clock() + tt = time.time() if name not in self.cp: self.cp[name] = 0. if ignore: @@ -36,12 +36,11 @@ def display(self): if not self.enabled: return self.iter += 1 - print "******* Profiling *******" - for n in self.cp: - ms = self.cp[n] + print("******* Profiling *******") + for n, ms in sorted(self.cp.items(), key=lambda x: -x[1]): if n in self.cp_ignored: - print "%30s: %7.2f perc: %1.0f" % (n, ms*1000.0, ms/self.tot*100), " IGNORED" + print("%30s: %7.2f percent: %3.0f IGNORED" % (n, ms*1000.0, ms/self.tot*100)) else: - print "%30s: %7.2f perc: %1.0f" % (n, ms*1000.0, ms/self.tot*100) - print "Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot) + print("%30s: %7.2f percent: %3.0f" % (n, ms*1000.0, ms/self.tot*100)) + print("Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot)) diff --git a/common/realtime.py b/common/realtime.py index e84e6eb490ecac..7fe183fb23abca 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -1,7 +1,6 @@ """Utilities for reading real time clocks and keeping soft real time constraints.""" import os import time -import ctypes import platform import threading import subprocess @@ -107,5 +106,3 @@ def monitor_time(self): self._remaining = remaining return lagged -if __name__ == "__main__": - print sec_since_boot() diff --git a/selfdrive/radar/__init__.py b/common/transformations/__init__.py similarity index 100% rename from selfdrive/radar/__init__.py rename to common/transformations/__init__.py diff --git a/common/transformations/camera.py b/common/transformations/camera.py new file mode 100644 index 00000000000000..e7472f53302f9e --- /dev/null +++ b/common/transformations/camera.py @@ -0,0 +1,115 @@ +import numpy as np +import common.transformations.orientation as orient + +FULL_FRAME_SIZE = (1164, 874) +W, H = FULL_FRAME_SIZE[0], FULL_FRAME_SIZE[1] +eon_focal_length = FOCAL = 910.0 + +# aka 'K' aka camera_frame_from_view_frame +eon_intrinsics = np.array([ + [FOCAL, 0., W/2.], + [ 0., FOCAL, H/2.], + [ 0., 0., 1.]]) + +# aka 'K_inv' aka view_frame_from_camera_frame +eon_intrinsics_inv = np.linalg.inv(eon_intrinsics) + + +# device/mesh : x->forward, y-> right, z->down +# view : x->right, y->down, z->forward +device_frame_from_view_frame = np.array([ + [ 0., 0., 1.], + [ 1., 0., 0.], + [ 0., 1., 0.] +]) +view_frame_from_device_frame = device_frame_from_view_frame.T + + +def get_calib_from_vp(vp): + vp_norm = normalize(vp) + yaw_calib = np.arctan(vp_norm[0]) + pitch_calib = np.arctan(vp_norm[1]*np.cos(yaw_calib)) + # TODO should be, this but written + # to be compatible with meshcalib and + # get_view_frame_from_road_fram + #pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib)) + roll_calib = 0 + return roll_calib, pitch_calib, yaw_calib + +# aka 'extrinsic_matrix' +# road : x->forward, y -> left, z->up +def get_view_frame_from_road_frame(roll, pitch, yaw, height): + # TODO + # calibration pitch is currently defined + # opposite to pitch in device frame + pitch = -pitch + device_from_road = orient.rot_from_euler([roll, pitch, yaw]).dot(np.diag([1, -1, -1])) + view_from_road = view_frame_from_device_frame.dot(device_from_road) + return np.hstack((view_from_road, [[0], [height], [0]])) + + +def vp_from_ke(m): + """ + Computes the vanishing point from the product of the intrinsic and extrinsic + matrices C = KE. + + The vanishing point is defined as lim x->infinity C (x, 0, 0, 1).T + """ + return (m[0, 0]/m[2,0], m[1,0]/m[2,0]) + +def roll_from_ke(m): + # note: different from calibration.h/RollAnglefromKE: i think that one's just wrong + return np.arctan2(-(m[1, 0] - m[1, 1] * m[2, 0] / m[2, 1]), + -(m[0, 0] - m[0, 1] * m[2, 0] / m[2, 1])) + +def normalize(img_pts): + # normalizes image coordinates + # accepts single pt or array of pts + img_pts = np.array(img_pts) + input_shape = img_pts.shape + img_pts = np.atleast_2d(img_pts) + img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1)))) + img_pts_normalized = eon_intrinsics_inv.dot(img_pts.T).T + img_pts_normalized[(img_pts < 0).any(axis=1)] = np.nan + return img_pts_normalized[:,:2].reshape(input_shape) + +def denormalize(img_pts): + # denormalizes image coordinates + # accepts single pt or array of pts + img_pts = np.array(img_pts) + input_shape = img_pts.shape + img_pts = np.atleast_2d(img_pts) + img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1)))) + img_pts_denormalized = eon_intrinsics.dot(img_pts.T).T + img_pts_denormalized[img_pts_denormalized[:,0] > W] = np.nan + img_pts_denormalized[img_pts_denormalized[:,0] < 0] = np.nan + img_pts_denormalized[img_pts_denormalized[:,1] > H] = np.nan + img_pts_denormalized[img_pts_denormalized[:,1] < 0] = np.nan + return img_pts_denormalized[:,:2].reshape(input_shape) + +def device_from_ecef(pos_ecef, orientation_ecef, pt_ecef): + # device from ecef frame + # device frame is x -> forward, y-> right, z -> down + # accepts single pt or array of pts + input_shape = pt_ecef.shape + pt_ecef = np.atleast_2d(pt_ecef) + ecef_from_device_rot = orient.rotations_from_quats(orientation_ecef) + device_from_ecef_rot = ecef_from_device_rot.T + pt_ecef_rel = pt_ecef - pos_ecef + pt_device = np.einsum('jk,ik->ij', device_from_ecef_rot, pt_ecef_rel) + return pt_device.reshape(input_shape) + +def img_from_device(pt_device): + # img coordinates from pts in device frame + # first transforms to view frame, then to img coords + # accepts single pt or array of pts + input_shape = pt_device.shape + pt_device = np.atleast_2d(pt_device) + pt_view = np.einsum('jk,ik->ij', view_frame_from_device_frame, pt_device) + + # This function should never return negative depths + pt_view[pt_view[:,2] < 0] = np.nan + + pt_img = pt_view/pt_view[:,2:3] + return pt_img.reshape(input_shape)[:,:2] + diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py new file mode 100644 index 00000000000000..568fb9bf2b3f4e --- /dev/null +++ b/common/transformations/coordinates.py @@ -0,0 +1,108 @@ +import numpy as np +""" +Coordinate transformation module. All methods accept arrays as input +with each row as a position. +""" + + + +a = 6378137 +b = 6356752.3142 +esq = 6.69437999014 * 0.001 +e1sq = 6.73949674228 * 0.001 + + +def geodetic2ecef(geodetic, radians=False): + geodetic = np.array(geodetic) + input_shape = geodetic.shape + geodetic = np.atleast_2d(geodetic) + + ratio = 1.0 if radians else (np.pi / 180.0) + lat = ratio*geodetic[:,0] + lon = ratio*geodetic[:,1] + alt = geodetic[:,2] + + xi = np.sqrt(1 - esq * np.sin(lat)**2) + x = (a / xi + alt) * np.cos(lat) * np.cos(lon) + y = (a / xi + alt) * np.cos(lat) * np.sin(lon) + z = (a / xi * (1 - esq) + alt) * np.sin(lat) + ecef = np.array([x, y, z]).T + return ecef.reshape(input_shape) + + +def ecef2geodetic(ecef, radians=False): + """ + Convert ECEF coordinates to geodetic using ferrari's method + """ + # Save shape and export column + ecef = np.atleast_1d(ecef) + input_shape = ecef.shape + ecef = np.atleast_2d(ecef) + x, y, z = ecef[:, 0], ecef[:, 1], ecef[:, 2] + + ratio = 1.0 if radians else (180.0 / np.pi) + + # Conver from ECEF to geodetic using Ferrari's methods + # https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution + r = np.sqrt(x * x + y * y) + Esq = a * a - b * b + F = 54 * b * b * z * z + G = r * r + (1 - esq) * z * z - esq * Esq + C = (esq * esq * F * r * r) / (pow(G, 3)) + S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) + P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) + Q = np.sqrt(1 + 2 * esq * esq * P) + r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ + P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) + U = np.sqrt(pow((r - esq * r_0), 2) + z * z) + V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) + Z_0 = b * b * z / (a * V) + h = U * (1 - b * b / (a * V)) + lat = ratio*np.arctan((z + e1sq * Z_0) / r) + lon = ratio*np.arctan2(y, x) + + # stack the new columns and return to the original shape + geodetic = np.column_stack((lat, lon, h)) + return geodetic.reshape(input_shape) + +class LocalCoord(object): + """ + Allows conversions to local frames. In this case NED. + That is: North East Down from the start position in + meters. + """ + def __init__(self, init_geodetic, init_ecef): + self.init_ecef = init_ecef + lat, lon, _ = (np.pi/180)*np.array(init_geodetic) + self.ned2ecef_matrix = np.array([[-np.sin(lat)*np.cos(lon), -np.sin(lon), -np.cos(lat)*np.cos(lon)], + [-np.sin(lat)*np.sin(lon), np.cos(lon), -np.cos(lat)*np.sin(lon)], + [np.cos(lat), 0, -np.sin(lat)]]) + self.ecef2ned_matrix = self.ned2ecef_matrix.T + + @classmethod + def from_geodetic(cls, init_geodetic): + init_ecef = geodetic2ecef(init_geodetic) + return LocalCoord(init_geodetic, init_ecef) + + @classmethod + def from_ecef(cls, init_ecef): + init_geodetic = ecef2geodetic(init_ecef) + return LocalCoord(init_geodetic, init_ecef) + + + def ecef2ned(self, ecef): + ecef = np.array(ecef) + return np.dot(self.ecef2ned_matrix, (ecef - self.init_ecef).T).T + + def ned2ecef(self, ned): + ned = np.array(ned) + # Transpose so that init_ecef will broadcast correctly for 1d or 2d ned. + return (np.dot(self.ned2ecef_matrix, ned.T).T + self.init_ecef) + + def geodetic2ned(self, geodetic): + ecef = geodetic2ecef(geodetic) + return self.ecef2ned(ecef) + + def ned2geodetic(self, ned): + ecef = self.ned2ecef(ned) + return ecef2geodetic(ecef) diff --git a/common/transformations/model.py b/common/transformations/model.py new file mode 100644 index 00000000000000..107c3d542c2036 --- /dev/null +++ b/common/transformations/model.py @@ -0,0 +1,112 @@ +import numpy as np + +from common.transformations.camera import eon_focal_length, \ + vp_from_ke, \ + get_view_frame_from_road_frame, \ + FULL_FRAME_SIZE + +# segnet + +SEGNET_SIZE = (512, 384) + +segnet_frame_from_camera_frame = np.array([ + [float(SEGNET_SIZE[0])/FULL_FRAME_SIZE[0], 0., ], + [ 0., float(SEGNET_SIZE[1])/FULL_FRAME_SIZE[1]]]) + + +# model + +MODEL_INPUT_SIZE = (320, 160) +MODEL_YUV_SIZE = (MODEL_INPUT_SIZE[0], MODEL_INPUT_SIZE[1] * 3 // 2) +MODEL_CX = MODEL_INPUT_SIZE[0]/2. +MODEL_CY = 21. + +model_zoom = 1.25 +model_height = 1.22 + +# canonical model transform +model_intrinsics = np.array( + [[ eon_focal_length / model_zoom, 0. , MODEL_CX], + [ 0. , eon_focal_length / model_zoom, MODEL_CY], + [ 0. , 0. , 1.]]) + + +# BIG model + +BIGMODEL_INPUT_SIZE = (864, 288) +BIGMODEL_YUV_SIZE = (BIGMODEL_INPUT_SIZE[0], BIGMODEL_INPUT_SIZE[1] * 3 // 2) + +bigmodel_zoom = 1. +bigmodel_intrinsics = np.array( + [[ eon_focal_length / bigmodel_zoom, 0. , 0.5 * BIGMODEL_INPUT_SIZE[0]], + [ 0. , eon_focal_length / bigmodel_zoom, 0.2 * BIGMODEL_INPUT_SIZE[1]], + [ 0. , 0. , 1.]]) + + +bigmodel_border = np.array([ + [0,0,1], + [BIGMODEL_INPUT_SIZE[0], 0, 1], + [BIGMODEL_INPUT_SIZE[0], BIGMODEL_INPUT_SIZE[1], 1], + [0, BIGMODEL_INPUT_SIZE[1], 1], +]) + + +model_frame_from_road_frame = np.dot(model_intrinsics, + get_view_frame_from_road_frame(0, 0, 0, model_height)) + +bigmodel_frame_from_road_frame = np.dot(bigmodel_intrinsics, + get_view_frame_from_road_frame(0, 0, 0, model_height)) + +model_frame_from_bigmodel_frame = np.dot(model_intrinsics, np.linalg.inv(bigmodel_intrinsics)) + +# 'camera from model camera' +def get_model_height_transform(camera_frame_from_road_frame, height): + camera_frame_from_road_ground = np.dot(camera_frame_from_road_frame, np.array([ + [1, 0, 0], + [0, 1, 0], + [0, 0, 0], + [0, 0, 1], + ])) + + camera_frame_from_road_high = np.dot(camera_frame_from_road_frame, np.array([ + [1, 0, 0], + [0, 1, 0], + [0, 0, height - model_height], + [0, 0, 1], + ])) + + road_high_from_camera_frame = np.linalg.inv(camera_frame_from_road_high) + high_camera_from_low_camera = np.dot(camera_frame_from_road_ground, road_high_from_camera_frame) + + return high_camera_from_low_camera + + +# camera_frame_from_model_frame aka 'warp matrix' +# was: calibration.h/CalibrationTransform +def get_camera_frame_from_model_frame(camera_frame_from_road_frame, height): + vp = vp_from_ke(camera_frame_from_road_frame) + + model_camera_from_model_frame = np.array([ + [model_zoom, 0., vp[0] - MODEL_CX * model_zoom], + [ 0., model_zoom, vp[1] - MODEL_CY * model_zoom], + [ 0., 0., 1.], + ]) + + # This function is super slow, so skip it if height is very close to canonical + # TODO: speed it up! + if abs(height - model_height) > 0.001: # + camera_from_model_camera = get_model_height_transform(camera_frame_from_road_frame, height) + else: + camera_from_model_camera = np.eye(3) + + return np.dot(camera_from_model_camera, model_camera_from_model_frame) + + +def get_camera_frame_from_bigmodel_frame(camera_frame_from_road_frame): + camera_frame_from_ground = camera_frame_from_road_frame[:, (0, 1, 3)] + bigmodel_frame_from_ground = bigmodel_frame_from_road_frame[:, (0, 1, 3)] + + ground_from_bigmodel_frame = np.linalg.inv(bigmodel_frame_from_ground) + camera_frame_from_bigmodel_frame = np.dot(camera_frame_from_ground, ground_from_bigmodel_frame) + + return camera_frame_from_bigmodel_frame diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py new file mode 100644 index 00000000000000..9e4edd456b27d6 --- /dev/null +++ b/common/transformations/orientation.py @@ -0,0 +1,293 @@ +import numpy as np +from numpy import dot, inner, array, linalg +from common.transformations.coordinates import LocalCoord + + +''' +Vectorized functions that transform between +rotation matrices, euler angles and quaternions. +All support lists, array or array of arrays as inputs. +Supports both x2y and y_from_x format (y_from_x preferred!). +''' + +def euler2quat(eulers): + eulers = array(eulers) + if len(eulers.shape) > 1: + output_shape = (-1,4) + else: + output_shape = (4,) + eulers = np.atleast_2d(eulers) + gamma, theta, psi = eulers[:,0], eulers[:,1], eulers[:,2] + + q0 = np.cos(gamma / 2) * np.cos(theta / 2) * np.cos(psi / 2) + \ + np.sin(gamma / 2) * np.sin(theta / 2) * np.sin(psi / 2) + q1 = np.sin(gamma / 2) * np.cos(theta / 2) * np.cos(psi / 2) - \ + np.cos(gamma / 2) * np.sin(theta / 2) * np.sin(psi / 2) + q2 = np.cos(gamma / 2) * np.sin(theta / 2) * np.cos(psi / 2) + \ + np.sin(gamma / 2) * np.cos(theta / 2) * np.sin(psi / 2) + q3 = np.cos(gamma / 2) * np.cos(theta / 2) * np.sin(psi / 2) - \ + np.sin(gamma / 2) * np.sin(theta / 2) * np.cos(psi / 2) + + quats = array([q0, q1, q2, q3]).T + for i in xrange(len(quats)): + if quats[i,0] < 0: + quats[i] = -quats[i] + return quats.reshape(output_shape) + + +def quat2euler(quats): + quats = array(quats) + if len(quats.shape) > 1: + output_shape = (-1,3) + else: + output_shape = (3,) + quats = np.atleast_2d(quats) + q0, q1, q2, q3 = quats[:,0], quats[:,1], quats[:,2], quats[:,3] + + gamma = np.arctan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1**2 + q2**2)) + theta = np.arcsin(2 * (q0 * q2 - q3 * q1)) + psi = np.arctan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2**2 + q3**2)) + + eulers = array([gamma, theta, psi]).T + return eulers.reshape(output_shape) + + +def quat2rot(quats): + quats = array(quats) + input_shape = quats.shape + quats = np.atleast_2d(quats) + Rs = np.zeros((quats.shape[0], 3, 3)) + q0 = quats[:, 0] + q1 = quats[:, 1] + q2 = quats[:, 2] + q3 = quats[:, 3] + Rs[:, 0, 0] = q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3 + Rs[:, 0, 1] = 2 * (q1 * q2 - q0 * q3) + Rs[:, 0, 2] = 2 * (q0 * q2 + q1 * q3) + Rs[:, 1, 0] = 2 * (q1 * q2 + q0 * q3) + Rs[:, 1, 1] = q0 * q0 - q1 * q1 + q2 * q2 - q3 * q3 + Rs[:, 1, 2] = 2 * (q2 * q3 - q0 * q1) + Rs[:, 2, 0] = 2 * (q1 * q3 - q0 * q2) + Rs[:, 2, 1] = 2 * (q0 * q1 + q2 * q3) + Rs[:, 2, 2] = q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3 + + if len(input_shape) < 2: + return Rs[0] + else: + return Rs + + +def rot2quat(rots): + input_shape = rots.shape + if len(input_shape) < 3: + rots = array([rots]) + K3 = np.empty((len(rots), 4, 4)) + K3[:, 0, 0] = (rots[:, 0, 0] - rots[:, 1, 1] - rots[:, 2, 2]) / 3.0 + K3[:, 0, 1] = (rots[:, 1, 0] + rots[:, 0, 1]) / 3.0 + K3[:, 0, 2] = (rots[:, 2, 0] + rots[:, 0, 2]) / 3.0 + K3[:, 0, 3] = (rots[:, 1, 2] - rots[:, 2, 1]) / 3.0 + K3[:, 1, 0] = K3[:, 0, 1] + K3[:, 1, 1] = (rots[:, 1, 1] - rots[:, 0, 0] - rots[:, 2, 2]) / 3.0 + K3[:, 1, 2] = (rots[:, 2, 1] + rots[:, 1, 2]) / 3.0 + K3[:, 1, 3] = (rots[:, 2, 0] - rots[:, 0, 2]) / 3.0 + K3[:, 2, 0] = K3[:, 0, 2] + K3[:, 2, 1] = K3[:, 1, 2] + K3[:, 2, 2] = (rots[:, 2, 2] - rots[:, 0, 0] - rots[:, 1, 1]) / 3.0 + K3[:, 2, 3] = (rots[:, 0, 1] - rots[:, 1, 0]) / 3.0 + K3[:, 3, 0] = K3[:, 0, 3] + K3[:, 3, 1] = K3[:, 1, 3] + K3[:, 3, 2] = K3[:, 2, 3] + K3[:, 3, 3] = (rots[:, 0, 0] + rots[:, 1, 1] + rots[:, 2, 2]) / 3.0 + q = np.empty((len(rots), 4)) + for i in xrange(len(rots)): + _, eigvecs = linalg.eigh(K3[i].T) + eigvecs = eigvecs[:,3:] + q[i, 0] = eigvecs[-1] + q[i, 1:] = -eigvecs[:-1].flatten() + if q[i, 0] < 0: + q[i] = -q[i] + + if len(input_shape) < 3: + return q[0] + else: + return q + + +def euler2rot(eulers): + return rotations_from_quats(euler2quat(eulers)) + + +def rot2euler(rots): + return quat2euler(quats_from_rotations(rots)) + + +quats_from_rotations = rot2quat +quat_from_rot = rot2quat +rotations_from_quats = quat2rot +rot_from_quat= quat2rot +rot_from_quat= quat2rot +euler_from_rot = rot2euler +euler_from_quat = quat2euler +rot_from_euler = euler2rot +quat_from_euler = euler2quat + + + + + + +''' +Random helpers below +''' + + +def quat_product(q, r): + t = np.zeros(4) + t[0] = r[0] * q[0] - r[1] * q[1] - r[2] * q[2] - r[3] * q[3] + t[1] = r[0] * q[1] + r[1] * q[0] - r[2] * q[3] + r[3] * q[2] + t[2] = r[0] * q[2] + r[1] * q[3] + r[2] * q[0] - r[3] * q[1] + t[3] = r[0] * q[3] - r[1] * q[2] + r[2] * q[1] + r[3] * q[0] + return t + + +def rot_matrix(roll, pitch, yaw): + cr, sr = np.cos(roll), np.sin(roll) + cp, sp = np.cos(pitch), np.sin(pitch) + cy, sy = np.cos(yaw), np.sin(yaw) + rr = array([[1,0,0],[0, cr,-sr],[0, sr, cr]]) + rp = array([[cp,0,sp],[0, 1,0],[-sp, 0, cp]]) + ry = array([[cy,-sy,0],[sy, cy,0],[0, 0, 1]]) + return ry.dot(rp.dot(rr)) + + +def rot(axis, angle): + # Rotates around an arbitrary axis + ret_1 = (1 - np.cos(angle)) * array([[axis[0]**2, axis[0] * axis[1], axis[0] * axis[2]], [ + axis[1] * axis[0], axis[1]**2, axis[1] * axis[2] + ], [axis[2] * axis[0], axis[2] * axis[1], axis[2]**2]]) + ret_2 = np.cos(angle) * np.eye(3) + ret_3 = np.sin(angle) * array([[0, -axis[2], axis[1]], [axis[2], 0, -axis[0]], + [-axis[1], axis[0], 0]]) + return ret_1 + ret_2 + ret_3 + + +def ecef_euler_from_ned(ned_ecef_init, ned_pose): + ''' + Got it from here: + Using Rotations to Build Aerospace Coordinate Systems + -Don Koks + ''' + converter = LocalCoord.from_ecef(ned_ecef_init) + x0 = converter.ned2ecef([1, 0, 0]) - converter.ned2ecef([0, 0, 0]) + y0 = converter.ned2ecef([0, 1, 0]) - converter.ned2ecef([0, 0, 0]) + z0 = converter.ned2ecef([0, 0, 1]) - converter.ned2ecef([0, 0, 0]) + + x1 = rot(z0, ned_pose[2]).dot(x0) + y1 = rot(z0, ned_pose[2]).dot(y0) + z1 = rot(z0, ned_pose[2]).dot(z0) + + x2 = rot(y1, ned_pose[1]).dot(x1) + y2 = rot(y1, ned_pose[1]).dot(y1) + z2 = rot(y1, ned_pose[1]).dot(z1) + + x3 = rot(x2, ned_pose[0]).dot(x2) + y3 = rot(x2, ned_pose[0]).dot(y2) + #z3 = rot(x2, ned_pose[0]).dot(z2) + + x0 = array([1, 0, 0]) + y0 = array([0, 1, 0]) + z0 = array([0, 0, 1]) + + psi = np.arctan2(inner(x3, y0), inner(x3, x0)) + theta = np.arctan2(-inner(x3, z0), np.sqrt(inner(x3, x0)**2 + inner(x3, y0)**2)) + y2 = rot(z0, psi).dot(y0) + z2 = rot(y2, theta).dot(z0) + phi = np.arctan2(inner(y3, z2), inner(y3, y2)) + + ret = array([phi, theta, psi]) + return ret + + +def ned_euler_from_ecef(ned_ecef_init, ecef_poses): + ''' + Got the math from here: + Using Rotations to Build Aerospace Coordinate Systems + -Don Koks + + Also accepts array of ecef_poses and array of ned_ecef_inits. + Where each row is a pose and an ecef_init. + ''' + ned_ecef_init = array(ned_ecef_init) + ecef_poses = array(ecef_poses) + output_shape = ecef_poses.shape + ned_ecef_init = np.atleast_2d(ned_ecef_init) + ecef_poses = np.atleast_2d(ecef_poses) + + ned_poses = np.zeros(ecef_poses.shape) + for i, ecef_pose in enumerate(ecef_poses): + converter = LocalCoord.from_ecef(ned_ecef_init[i]) + x0 = array([1, 0, 0]) + y0 = array([0, 1, 0]) + z0 = array([0, 0, 1]) + + x1 = rot(z0, ecef_pose[2]).dot(x0) + y1 = rot(z0, ecef_pose[2]).dot(y0) + z1 = rot(z0, ecef_pose[2]).dot(z0) + + x2 = rot(y1, ecef_pose[1]).dot(x1) + y2 = rot(y1, ecef_pose[1]).dot(y1) + z2 = rot(y1, ecef_pose[1]).dot(z1) + + x3 = rot(x2, ecef_pose[0]).dot(x2) + y3 = rot(x2, ecef_pose[0]).dot(y2) + #z3 = rot(x2, ecef_pose[0]).dot(z2) + + x0 = converter.ned2ecef([1, 0, 0]) - converter.ned2ecef([0, 0, 0]) + y0 = converter.ned2ecef([0, 1, 0]) - converter.ned2ecef([0, 0, 0]) + z0 = converter.ned2ecef([0, 0, 1]) - converter.ned2ecef([0, 0, 0]) + + psi = np.arctan2(inner(x3, y0), inner(x3, x0)) + theta = np.arctan2(-inner(x3, z0), np.sqrt(inner(x3, x0)**2 + inner(x3, y0)**2)) + y2 = rot(z0, psi).dot(y0) + z2 = rot(y2, theta).dot(z0) + phi = np.arctan2(inner(y3, z2), inner(y3, y2)) + ned_poses[i] = array([phi, theta, psi]) + + return ned_poses.reshape(output_shape) + + +def ecef2car(car_ecef, psi, theta, points_ecef, ned_converter): + """ + TODO: add roll rotation + Converts an array of points in ecef coordinates into + x-forward, y-left, z-up coordinates + Parameters + ---------- + psi: yaw, radian + theta: pitch, radian + Returns + ------- + [x, y, z] coordinates in car frame + """ + + # input is an array of points in ecef cocrdinates + # output is an array of points in car's coordinate (x-front, y-left, z-up) + + # convert points to NED + points_ned = [] + for p in points_ecef: + points_ned.append(ned_converter.ecef2ned_matrix.dot(array(p) - car_ecef)) + + points_ned = np.vstack(points_ned).T + + # n, e, d -> x, y, z + # Calculate relative postions and rotate wrt to heading and pitch of car + invert_R = array([[1., 0., 0.], [0., -1., 0.], [0., 0., -1.]]) + + c, s = np.cos(psi), np.sin(psi) + yaw_R = array([[c, s, 0.], [-s, c, 0.], [0., 0., 1.]]) + + c, s = np.cos(theta), np.sin(theta) + pitch_R = array([[c, 0., -s], [0., 1., 0.], [s, 0., c]]) + + return dot(pitch_R, dot(yaw_R, dot(invert_R, points_ned))) diff --git a/installer/updater/updater b/installer/updater/updater new file mode 100755 index 00000000000000..a5defb4108b556 Binary files /dev/null and b/installer/updater/updater differ diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh new file mode 100755 index 00000000000000..41f8a607cf9ca5 --- /dev/null +++ b/launch_chffrplus.sh @@ -0,0 +1,32 @@ +#!/usr/bin/bash + +if [ -z "$PASSIVE" ]; then + export PASSIVE="1" +fi + +function launch { + # apply update + if [ "$(git rev-parse HEAD)" != "$(git rev-parse @{u})" ]; then + git reset --hard @{u} && + git clean -xdf && + exec "${BASH_SOURCE[0]}" + fi + + # no cpu rationing for now + echo 0-3 > /dev/cpuset/background/cpus + echo 0-3 > /dev/cpuset/system-background/cpus + echo 0-3 > /dev/cpuset/foreground/boost/cpus + echo 0-3 > /dev/cpuset/foreground/cpus + echo 0-3 > /dev/cpuset/android/cpus + + export PYTHONPATH="$PWD" + + # start manager + cd selfdrive + ./manager.py + + # if broken, keep on screen error + while true; do sleep 1; done +} + +launch diff --git a/launch_openpilot.sh b/launch_openpilot.sh index 4b55f80f110af3..1525e1715f99c2 100755 --- a/launch_openpilot.sh +++ b/launch_openpilot.sh @@ -1,39 +1,5 @@ #!/usr/bin/bash -function launch { - # apply update - if [ "$(git rev-parse HEAD)" != "$(git rev-parse @{u})" ]; then - git reset --hard @{u} && - git clean -xdf && - exec "${BASH_SOURCE[0]}" - fi +export PASSIVE="0" +exec ./launch_chffrplus.sh - # check if NEOS update is required - while [ "$(cat /VERSION)" -lt 4 ] && [ ! -e /data/media/0/noupdate ]; do - curl -o /tmp/updater https://neos.comma.ai/updater && chmod +x /tmp/updater && /tmp/updater - sleep 10 - done - - # no cpu rationing for now - echo 0-3 > /dev/cpuset/background/cpus - echo 0-3 > /dev/cpuset/system-background/cpus - echo 0-3 > /dev/cpuset/foreground/boost/cpus - echo 0-3 > /dev/cpuset/foreground/cpus - echo 0-3 > /dev/cpuset/android/cpus - - # wait for network - (cd selfdrive/ui/spinner && exec ./spinner 'waiting for network...') & spin_pid=$! - until ping -W 1 -c 1 8.8.8.8; do sleep 1; done - kill $spin_pid - - export PYTHONPATH="$PWD" - - # start manager - cd selfdrive - ./manager.py - - # if broken, keep on screen error - while true; do sleep 1; done -} - -launch diff --git a/opendbc/README.md b/opendbc/README.md index 39185bb86728f9..eec42dfefa7ff2 100644 --- a/opendbc/README.md +++ b/opendbc/README.md @@ -8,7 +8,7 @@ The project to democratize access to the decoder ring of your car. ### DBC file basics A DBC file encodes, in a humanly readable way, the information needed to understand a vehicle's CAN bus traffic. A vehicle might have multiple CAN buses and every CAN bus is represented by its own dbc file. -Wondering what's the DBC file format? [Here](http://www.socialledge.com/sjsu/index.php?title=DBC_Format) a good overview. +Wondering what's the DBC file format? [Here](http://www.socialledge.com/sjsu/index.php?title=DBC_Format) and [Here](https://github.com/stefanhoelzl/CANpy/blob/master/docs/DBC_Specification.md) a couple of good overviews. ### How to start reverse engineering cars @@ -16,15 +16,19 @@ Wondering what's the DBC file format? [Here](http://www.socialledge.com/sjsu/ind Use [panda](https://github.com/commaai/panda) to connect your car to a computer. +### DBC file preprocessor + +DBC files for different models of the same brand have a lot of overlap. Therefore, we wrote a preprocessor to create DBC files from a brand DBC file and a model specific DBC file. The source DBC files can be found in the generator folder. After changing one of the files run the generator.py script to regenerate the output files. These output files will be placed in the root of the opendbc repository and are suffixed by _generated. + ### Good practices for contributing to opendbc -- Comments: the best way to store comments is to add them directly to the DBC files. For example: +- Comments: the best way to store comments is to add them directly to the DBC files. For example: ``` CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; ``` is a comment that refers to signal `LONG_ACCEL` in message `490`. Using comments is highly recommended, especially for doubts and uncertainties. [cabana](https://community.comma.ai/cabana/) can easily display/add/edit comments to signals and messages. -- Units: when applicable, it's recommended to convert signals into physical units, by using a proper signal factor. Using a SI unit is preferred, unless a non-SI unit rounds the signal factor much better. +- Units: when applicable, it's recommended to convert signals into physical units, by using a proper signal factor. Using a SI unit is preferred, unless a non-SI unit rounds the signal factor much better. For example: ``` SG_ VEHICLE_SPEED : 7|15@0+ (0.00278,0) [0|70] "m/s" PCM @@ -36,7 +40,7 @@ For example: However, the cleanest option is really: ``` SG_ VEHICLE_SPEED : 7|15@0+ (0.01,0) [0|250] "kph" PCM - ``` + ``` - Signal's size: always use the smallest amount of bits possible. For example, let's say I'm reverse engineering the gas pedal position and I've determined that it's in a 3 bytes message. For 0% pedal position I read a message value of `0x00 0x00 0x00`, while for 100% of pedal position I read `0x64 0x00 0x00`: clearly, the gas pedal position is within the first byte of the message and I might be tempted to define the signal `GAS_POS` as: ``` diff --git a/opendbc/acura_ilx_2016_can.dbc b/opendbc/acura_ilx_2016_can.dbc deleted file mode 100644 index 3f31205ab3c4dc..00000000000000 --- a/opendbc/acura_ilx_2016_can.dbc +++ /dev/null @@ -1,323 +0,0 @@ -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_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS - -BO_ 304 GAS_PEDAL2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 398 XXX_3: 3 XXX - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 419 GEARBOX: 8 PCM - SG_ GEAR : 7|8@0+ (1,0) [0|256] "" NEO - SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 428 XXX_4: 8 XXX - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 476 XXX_5: 4 XXX - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM - -BO_ 512 GAS_COMMAND: 3 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 5 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - -BO_ 542 XXX_6: 7 XXX - -BO_ 545 XXX_7: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 777 XXX_8: 8 XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ HUD_DISTANCE_3 : 52|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|3] "" BDY - -BO_ 800 XXX_9: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 808 XXX_10: 8 XXX - -BO_ 819 XXX_11: 7 XXX - -BO_ 821 XXX_12: 5 XXX - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 882 XXX_13: 2 XXX - -BO_ 884 XXX_14: 7 XXX - -BO_ 887 XXX_15: 8 XXX - -BO_ 888 XXX_16: 8 XXX - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - -BO_ 923 XXX_18: 2 XXX - -BO_ 929 XXX_19: 4 XXX - -BO_ 983 XXX_20: 8 XXX - -BO_ 985 XXX_21: 3 XXX - -BO_ 1024 XXX_22: 5 XXX - -BO_ 1027 XXX_23: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1030 XXX_24: 5 VSA - -BO_ 1034 XXX_25: 5 XXX - -BO_ 1036 XXX_26: 8 XXX - -BO_ 1039 XXX_27: 8 XXX - -BO_ 1057 XXX_28: 5 EPS - -BO_ 1064 XXX_29: 7 XXX - -BO_ 1108 XXX_30: 8 XXX - -BO_ 1365 XXX_31: 5 XXX - -BO_ 1600 XXX_32: 5 XXX - -BO_ 1601 XXX_33: 8 XXX - -BO_TX_BU_ 228 : NEO,ADAS; -BO_TX_BU_ 506 : NEO,ADAS; -BO_TX_BU_ 780 : NEO,ADAS; -BO_TX_BU_ 829 : NEO,ADAS; - -CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; -VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; -VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; -VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/acura_ilx_2016_can_generated.dbc b/opendbc/acura_ilx_2016_can_generated.dbc new file mode 100644 index 00000000000000..b0c16c814cd84c --- /dev/null +++ b/opendbc/acura_ilx_2016_can_generated.dbc @@ -0,0 +1,306 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "acura_ilx_2016_can.dbc starts here" + + + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/acura_ilx_2016_nidec.dbc b/opendbc/acura_ilx_2016_nidec.dbc index e2810b40ac2920..e73fcc422177be 100644 --- a/opendbc/acura_ilx_2016_nidec.dbc +++ b/opendbc/acura_ilx_2016_nidec.dbc @@ -1,185 +1,185 @@ -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_: ADAS RADAR NEO XXX - - -BO_ 768 VEHICLE_STATE: 8 ADAS - SG_ SET_ME_XF9 : 7|8@0+ (1,0) [0|255] "" Vector__XXX - SG_ VEHICLE_SPEED : 15|8@0+ (1,0) [0|255] "kph" Vector__XXX - -BO_ 769 VEHICLE_STATE2: 8 ADAS - SG_ SET_ME_0F18510 : 7|28@0+ (1,0) [0|268435455] "" Vector__XXX - SG_ SET_ME_25A0000 : 27|28@0+ (1,0) [0|268435455] "" Vector__XXX - -BO_ 1024 RADAR_DIAGNOSTIC: 8 RADAR - SG_ RADAR_STATE : 7|8@0+ (1,0) [0|255] "" NEO - -BO_ 1040 XXX_101: 8 RADAR - -BO_ 1041 XXX_102: 8 RADAR - -BO_ 1042 XXX_103: 8 RADAR - -BO_ 1043 XXX_104: 8 RADAR - -BO_ 1044 XXX_105: 8 RADAR - -BO_ 1045 XXX_106: 8 RADAR - -BO_ 1046 XXX_107: 8 RADAR - -BO_ 1047 XXX_108: 8 RADAR - -BO_ 1056 XXX_109: 8 RADAR - -BO_ 1057 XXX_110: 8 RADAR - -BO_ 1058 XXX_111: 8 RADAR - -BO_ 1059 XXX_112: 8 RADAR - -BO_ 1060 XXX_113: 8 RADAR - -BO_ 1072 TRACK_0: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1073 TRACK_1: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1074 TRACK_2: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1075 TRACK_3: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1076 TRACK_4: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1077 TRACK_5: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1078 TRACK_6: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1079 TRACK_7: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1080 TRACK_8: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1081 TRACK_9: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1088 TRACK_10: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1089 TRACK_11: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1090 TRACK_12: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1091 TRACK_13: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1092 TRACK_14: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1093 TRACK_15: 8 RADAR - SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO - SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO - SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO - SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO - -BO_ 1279 XXX_114: 8 RADAR - -BO_ 1280 XXX_115: 8 RADAR - -BO_ 1296 XXX_116: 8 RADAR - -BO_ 1297 XXX_117: 8 RADAR - -BO_TX_BU_ 768 : NEO,ADAS; -BO_TX_BU_ 769 : NEO,ADAS; - - -CM_ SG_ 1024 RADAR_STATE "need to find out more diagnostic values"; -VAL_ 1024 RADAR_STATE 121 "ok" 110 "faulted"; +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_: ADAS RADAR NEO XXX + + +BO_ 768 VEHICLE_STATE: 8 ADAS + SG_ SET_ME_XF9 : 7|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ VEHICLE_SPEED : 15|8@0+ (1,0) [0|255] "kph" Vector__XXX + +BO_ 769 VEHICLE_STATE2: 8 ADAS + SG_ SET_ME_0F18510 : 7|28@0+ (1,0) [0|268435455] "" Vector__XXX + SG_ SET_ME_25A0000 : 27|28@0+ (1,0) [0|268435455] "" Vector__XXX + +BO_ 1024 RADAR_DIAGNOSTIC: 8 RADAR + SG_ RADAR_STATE : 7|8@0+ (1,0) [0|255] "" NEO + +BO_ 1040 XXX_101: 8 RADAR + +BO_ 1041 XXX_102: 8 RADAR + +BO_ 1042 XXX_103: 8 RADAR + +BO_ 1043 XXX_104: 8 RADAR + +BO_ 1044 XXX_105: 8 RADAR + +BO_ 1045 XXX_106: 8 RADAR + +BO_ 1046 XXX_107: 8 RADAR + +BO_ 1047 XXX_108: 8 RADAR + +BO_ 1056 XXX_109: 8 RADAR + +BO_ 1057 XXX_110: 8 RADAR + +BO_ 1058 XXX_111: 8 RADAR + +BO_ 1059 XXX_112: 8 RADAR + +BO_ 1060 XXX_113: 8 RADAR + +BO_ 1072 TRACK_0: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1073 TRACK_1: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1074 TRACK_2: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1075 TRACK_3: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1076 TRACK_4: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1077 TRACK_5: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1078 TRACK_6: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1079 TRACK_7: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1080 TRACK_8: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1081 TRACK_9: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1088 TRACK_10: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1089 TRACK_11: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1090 TRACK_12: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1091 TRACK_13: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1092 TRACK_14: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1093 TRACK_15: 8 RADAR + SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO + SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO + SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO + SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO + +BO_ 1279 XXX_114: 8 RADAR + +BO_ 1280 XXX_115: 8 RADAR + +BO_ 1296 XXX_116: 8 RADAR + +BO_ 1297 XXX_117: 8 RADAR + +BO_TX_BU_ 768 : NEO,ADAS; +BO_TX_BU_ 769 : NEO,ADAS; + + +CM_ SG_ 1024 RADAR_STATE "need to find out more diagnostic values"; +VAL_ 1024 RADAR_STATE 121 "ok" 110 "faulted" 105 "wrong_config"; diff --git a/opendbc/acura_rdx_2018_can.dbc b/opendbc/acura_rdx_2018_can.dbc deleted file mode 100644 index 11f00188d10f19..00000000000000 --- a/opendbc/acura_rdx_2018_can.dbc +++ /dev/null @@ -1,315 +0,0 @@ -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_: INTERCEPTOR EBCM NEO CAM PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - -BO_ 316 XXX_3: 8 PCM - -BO_ 340 XXX_4: 8 PCM - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 392 GEARBOX: 6 XXX - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX - SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" NEO - SG_ GEAR : 36|5@0+ (1,0) [0|31] "" NEO - -BO_ 398 XXX_5: 3 PCM - -BO_ 399 STEER_STATUS: 6 EPS - SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - -BO_ 404 STEERING_CONTROL: 4 NEO - SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" EPS - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" EPS - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ PARKING_BREAK_LIGHT : 2|1@0+ (1,0) [0|1] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 426 XXX_6: 8 VSA - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 474 XXX_7: 5 VSA - -BO_ 476 XXX_8: 5 XXX - -BO_ 487 XXX_9: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 493 XXX_10: 3 VSA - -BO_ 506 BRAKE_COMMAND: 8 NEO - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM - SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM - SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM - SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM - -BO_ 507 XXX_11: 1 NEO - -BO_ 542 XXX_12: 7 XXX - -BO_ 545 XXX_13: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 661 XXX_14: 4 XXX - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 777 XXX_15: 8 XXX - -BO_ 780 ACC_HUD: 8 CAM - SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY - -BO_ 800 XXX_16: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO - SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 808 XXX_17: 8 XXX - -BO_ 829 LKAS_HUD_2: 5 CAM - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 882 XXX_18: 2 XXX - -BO_ 884 XXX_19: 7 XXX - -BO_ 888 XXX_20: 8 XXX - -BO_ 891 XXX_21: 8 XXX - -BO_ 923 XXX_23: 2 XXX - -BO_ 929 XXX_24: 8 XXX - -BO_ 983 XXX_25: 8 XXX - -BO_ 985 XXX_26: 3 XXX - -BO_ 1024 XXX_27: 5 XXX - -BO_ 1027 XXX_28: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 1033 XXX_29: 5 XXX - -BO_ 1036 XXX_30: 8 XXX - -BO_ 1039 XXX_31: 8 XXX - -BO_ 1057 XXX_32: 5 XXX - -BO_ 1064 XXX_32: 7 XXX - -BO_ 1108 XXX_33: 8 XXX - -BO_ 1125 XXX_34: 8 XXX - -BO_ 1296 XXX_35: 8 XXX - -BO_ 1365 XXX_36: 5 XXX - -BO_ 1424 XXX_37: 5 XXX - -BO_ 1600 XXX_38: 5 XXX - -BO_ 1601 XXX_39: 8 XXX - -BO_TX_BU_ 399 : NEO,CAM; -BO_TX_BU_ 506 : NEO,CAM; -BO_TX_BU_ 780 : NEO,CAM; -BO_TX_BU_ 829 : NEO,CAM; - - -CM_ SG_ 422 PARKING_BREAK_LIGHT "Believe this is just the dash light for the parking break"; -VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; -VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/acura_rdx_2018_can_generated.dbc b/opendbc/acura_rdx_2018_can_generated.dbc new file mode 100644 index 00000000000000..d60b90d750f399 --- /dev/null +++ b/opendbc/acura_rdx_2018_can_generated.dbc @@ -0,0 +1,294 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 392 GEARBOX: 6 XXX + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX + SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" EON + SG_ GEAR : 36|5@0+ (1,0) [0|31] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ PARKING_BRAKE_LIGHT : 2|1@0+ (1,0) [0|1] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 422 PARKING_BRAKE_LIGHT "Believe this is just the dash light for the parking break"; +VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; +VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/cadillac_ct6_chassis.dbc b/opendbc/cadillac_ct6_chassis.dbc new file mode 100644 index 00000000000000..9de969d762f9a2 --- /dev/null +++ b/opendbc/cadillac_ct6_chassis.dbc @@ -0,0 +1,95 @@ +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_: K182_PACM K43_PSCM K17_EBCM NEO K124_ASCM + + + +BO_ 823 PACMParkAssitCmd: 7 NEO + SG_ RollingCounter : 35|2@0+ (1,0) [0|0] "" NEO + SG_ SteeringWheelChecksum : 47|16@0+ (1,0) [0|0] "" NEO + SG_ SteeringWheelCmd : 23|16@0+ (1,0) [0|0] "" NEO + +BO_ 560 EBCMRegen: 6 K17_EBCM + SG_ Regen : 1|10@0+ (1,0) [0|0] "" NEO + +BO_ 338 ASCMLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASMode : 36|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 340 ASCMBLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASteeringCmdActive2 : 35|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 368 EBCMFrictionBrakeStatus: 8 K17_EBCM + SG_ FrictionBrakePressure : 23|16@0+ (1,0) [0|0] "" NEO + +BO_ 789 EBCMFrictionBrakeCmd: 5 K17_EBCM + SG_ RollingCounter : 37|6@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeMode : 7|4@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeChecksum : 23|16@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeCmd : 3|12@0- (1,0) [0|0] "" NEO + +BO_TX_BU_ 823 : K43_PSCM,NEO; +BO_TX_BU_ 789 : NEO,K17_EBCM; + + +CM_ BU_ K182_PACM "Parking Assist Control Module"; +CM_ BU_ K43_PSCM "Power Steering Control Module"; +CM_ BU_ K17_EBCM "Electronic Brake Control Module"; +CM_ BU_ NEO "Comma NEO"; +CM_ BU_ K124_ASCM "Active Safety Control Module"; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "UseGMParameterIDs" 0; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; + +VAL_ 338 LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 338 LKASMode 2 "supercruise" 1 "lkas" 0 "Inactive" ; diff --git a/opendbc/cadillac_ct6_object.dbc b/opendbc/cadillac_ct6_object.dbc new file mode 100644 index 00000000000000..d83ae672b16307 --- /dev/null +++ b/opendbc/cadillac_ct6_object.dbc @@ -0,0 +1,3470 @@ +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_: RRSRR_FO LRSRR_FO CIPM_FO _DOFIMU2_FO _DOFIMU1_FO DMS_FO AMM_FO EOCM2B_IMX6_FO EOCM2B_K2_FO EOCM2B_K1_FO EOCM2A_IMX6_FO EOCM2A_K2_FO EOCM2A_K1_FO NVS_FO Dummy_FO TestTool_FO LRR_FO RFSRR_FO LFSRR_FO RSRR_FO VIS_FO EOCM_F_FO VIS2_FO +VAL_TABLE_ vt_BooleanValues 1 "true" 0 "false" ; +VAL_TABLE_ FrntVsnInPthVehBrkNwSt 10 "Active" 5 "Inactive" ; +VAL_TABLE_ FrntVsnClostPedBrkNwSt 10 "Active" 5 "Inactive" ; +VAL_TABLE_ DrvrMonSysEngSt 7 "Unused and Reserved 1" 6 "Recovering" 5 "Tracking" 4 "Searching" 3 "Video test port only" 2 "Idle" 1 "Invalid state" 0 "Does not exist or DME" ; +VAL_TABLE_ DrvrMonEngUnrecvrFltCod 7 "Unused and Reserved 3" 6 "Unused and Reserved 2" 5 "Unused and Reserved 1" 4 "Vehicle power supply Errors" 3 "Problem with LED illuminators" 2 "Vehicle input signals Errors" 1 "Problem with imager" 0 "Ok" ; +VAL_TABLE_ DrvrMonEngRecvrFltCod 3 "Engine is unable to find a face" 2 "Input Images too dark" 1 "Input images too bright" 0 "Ok" ; +VAL_TABLE_ DrvrMntrSysVTP 1 "Video test port active" 0 "Video test port inactive" ; +VAL_TABLE_ DrvrAttnStatCnfdc 3 "High" 2 "Medium" 1 "Low" 0 "Lowest" ; +VAL_TABLE_ DrvrAttnStat 7 "Invalid" 6 "Driver is exhibiting sleep" 5 "Driver is exhibiting microsleep" 4 "Attention is Center Console" 3 "Attention is Drivers Lap" 2 "Attention is Off Road" 1 "Attention is On Road" 0 "Unknown" ; +VAL_TABLE_ PPSMd 7 "GNSS and RTX and DR and MM" 6 "DR ONLY" 5 "GNSS and RTX and DR" 4 "GNSS and SBAS and DR" 3 "GNSS and DR" 2 "GNSS and RTX" 1 "GNSS and SBAS" 0 "GNSS Standalone" ; +VAL_TABLE_ AdvDrvAstMpPrfShrtAcur 3 "Accuracy Is Unknown" 2 "Lowest Accuracy" 1 "Medium Accuracy" 0 "Highest Accuracy" ; +VAL_TABLE_ AdvDrAstMpStbRtOfWay 3 "Not Applicable" 2 "Unknown" 1 "Sub Path Has Right Of Way Over Path" 0 "Path Has Right Of Way Over Sub Path" ; +VAL_TABLE_ AdvDrAstMpStbPrtCalRut 3 "Not Applicable" 2 "Unknown" 1 "Path From This Point On Is Part Of Calculated Route" 0 "Path From This Point On Is Not Part Of Calculated Route" ; +VAL_TABLE_ AdvDrAstMpStbMsgTyp 7 "Unused and Reserved 2" 6 "Metadata" 5 "Profile Long" 4 "Profile Short" 3 "Stub" 2 "Segment" 1 "Position" 0 "Unused and Reserved 1" ; +VAL_TABLE_ AdvDrAstMpStbFmOfWay 15 "Not Applicable" 14 "Pedestrian Zone" 13 "Entrance To Or Exit To Service" 12 "Entrance To Or Exit Of A Car Park" 11 "Service Road Or Frontage Road" 10 "Slip Road per Ramp" 9 "Slip Road per Ramp On A Freeway Or Controlled Access Road" 8 "Parallel Road" 7 "Unused and Reserved 2" 6 "Unused and Reserved 1" 5 "Traffic Square per Special Traffic Figure" 4 "Roundabout Circle" 3 "Single Carriageway" 2 "Multiple Carriageway Or Multiply Digitized Road" 1 "Freeway Or Controlled Access Road That Is Not A Slip Road Or Ramp" 0 "Unknown" ; +VAL_TABLE_ AdvDrAstMpStbCmplxInsct 3 "Not Applicable" 2 "Unknown" 1 "Stub Is Part Of Complex Intersection" 0 "Stub Is Not Part Of Complex Intersection" ; +VAL_TABLE_ AdvDrAstMpSegTunl 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Tunnel" 0 "Segment Is Not A Part Of Tunnel" ; +VAL_TABLE_ AdvDrAstMpSegPrtCalRut 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Calculated Route" 0 "Segment Is Not Part Of Calculated Route" ; +VAL_TABLE_ AdvDrAstMpSegMsgTyp 7 "Unused and Reserved 2" 6 "Metadata" 5 "Profile Long" 4 "Profile Short" 3 "Stub" 2 "Segment" 1 "Position" 0 "Unused and Reserved 1" ; +VAL_TABLE_ AdvDrAstMpSegFrmOfWay 15 "Not Applicable" 14 "Pedestrian Zone" 13 "Entrance To Or Exit To Service" 12 "Entrance To Or Exit Of A Car Park" 11 "Service Road Or Frontage Road" 10 "Slip Road per Ramp" 9 "Slip Road per Ramp On A Freeway Or Controlled Access Road" 8 "Parallel Road" 7 "Unused and Reserved 2" 6 "Unused and Reserved 1" 5 "Traffic Square per Special Traffic Figure" 4 "Roundabout Circle" 3 "Single Carriageway" 2 "Multiple Carriageway Or Multiply Digitized Road" 1 "Freeway Or Controlled Access Road That Is Not A Slip Road or Ramp" 0 "Unknown" ; +VAL_TABLE_ AdvDrAstMpSegEffSdLmtTp 7 "Not Applicable" 6 "Explicit Snow" 5 "Explicit Rain" 4 "Explicit Time Of Day" 3 "Explicit By Day" 2 "Explicit By Night" 1 "Explicit On Traffic Sign" 0 "Implicit" ; +VAL_TABLE_ AdvDrAstMpSegDivdRd 3 "Not Applicable" 2 "Unkown" 1 "Segment Is Part Of Divided Road" 0 "Segment Is Not Part Of Divided Road" ; +VAL_TABLE_ AdvDrAstMpSegCmplxInsct 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Complex Intersection" 0 "Segment Is Not Part Of Complex Intersection" ; +VAL_TABLE_ AdvDrAstMpSegBrdg 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Bridge" 0 "Segment Not Part Of Bridge" ; +VAL_TABLE_ AdvDrAstMpSegBldUpAra 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Built Up Area" 0 "Segment Is Not Part Of Built Up Area" ; +VAL_TABLE_ AdvDrAstMpMtdtSpdUnt 1 "Miles Per Hour" 0 "Kilometers Per Hour" ; +VAL_TABLE_ AdvDrAstMpMtdtDrvSd 1 "Driving Side Right" 0 "Driving Side Left" ; +VAL_TABLE_ WSMR_WiFiAssnReq 3 "Unexpected Undefined Connection Behavior" 2 "Wi Fi association failed with available credentials" 1 "Failed to receive Wi Fi credentials after 255 attempts" 0 "SSID and Passphrase Request" ; +VAL_TABLE_ StrgColCommsFlt 2 "Disabled Communications DTC" 1 "No Communications Fault" 0 "Communications Fault" ; +VAL_TABLE_ CPMAPINFO4 1 "Hardware Or Software Error" 0 "No Hardware Or Software Error" ; +VAL_TABLE_ AdvDrvAstMpPrfShrt2Acur 3 "Accuracy Is Unknown" 2 "Lowest Accuracy" 1 "Medium Accuracy" 0 "Highest Accuracy" ; +VAL_TABLE_ InterLghtStat 1 "Interior Lights On" 0 "Interior Light Off" ; +VAL_TABLE_ VehLnStatConf 2 "High Confidence" 1 "Low Confidence" 0 "No Confidence" 3 "Very High Confidence" ; +VAL_TABLE_ VehLnStat 3 "Lane Change To Right" 2 "Lane Change To Left" 1 "Staying in Lane" 0 "Unkown" ; +VAL_TABLE_ HrznPrvdRstRq 1 "Reset Not Required" 0 "Reset Required" ; +VAL_TABLE_ ExptNxtTrnstnDirConf 3 "Very High Confidence" 2 "High Confidence" 1 "Low Confidence" 0 "No Confidence" ; +VAL_TABLE_ ExptNxtTrnstnDir 7 "Reserved4" 6 "Reserved3" 5 "Reserved2" 4 "Reserved1" 3 "Traversing Middle Transition" 2 "Traversing Next Transition Right" 1 "Traversing Next Transition Left" 0 "Unknown" ; +VAL_TABLE_ ADASISMsgTypRetrans 7 "GM System Specific" 6 "Meta Data" 5 "Profile Long" 4 "Profile Short" 3 "Stub" 2 "Segment" 1 "Position" 0 "Checksum" ; +VAL_TABLE_ NVSysStat 7 "Needs Headlights" 6 "Temporarily Unavailable" 5 "Not Dark" 4 "Needs Service" 3 "Active" 2 "Inactive" 1 "Initializing" 0 "Unknown" ; +VAL_TABLE_ NVSysPedWrnIndReq 3 "Unused & Reserved" 2 "Pedestrian Alert" 1 "Pedestrian Detected" 0 "None" ; +VAL_TABLE_ NVSysPedDetCstReq 2 "On" 1 "Off" 0 "No Value" ; +VAL_TABLE_ NVSysPedDetCsCrStVal 2 "On" 1 "Off" 0 "No Value" ; +VAL_TABLE_ FwVsnCinCoutPotT9Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT8Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT7Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT6Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT5Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT4Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT3Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT2Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT1Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT12Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT11Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT10Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ GFHBObjDirTrk8 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk7 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk6 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk5 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk4 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk3 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk2 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk1 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk8 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk7 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk6 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk5 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk4 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk3 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk2 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk1 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk8 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk7 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk6 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk5 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk4 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk3 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk2 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk1 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk8 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk7 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk6 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk5 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk4 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk3 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk2 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk1 0 "Invalid" 3 "Confident" 2 "Speculative" 1 "Highly Speculative" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev8 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev7 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev6 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev5 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev4 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev3 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev2 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev1 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car" 0 "Unknown" ; +VAL_TABLE_ CRL_Cnfdnc 7 "Reserved4" 6 "Reserved3" 5 "Reserved2" 4 "Reserved1" 3 "Best" 2 "Marking Present" 1 "Weak Marking" 0 "No Lane" ; +VAL_TABLE_ CLL_Cnfdnc 7 "Reserved4" 6 "Reserved3" 5 "Reserved2" 4 "Reserved1" 3 "Best" 2 "Marking Present" 1 "Weak Marking" 0 "No Lane" ; +VAL_TABLE_ VBBrkCtrlSt 4 "Release Control" 3 "Hold Vehicle" 2 "Apply Brake" 1 "Decrease Torque" 0 "No Action" ; +VAL_TABLE_ ObstacleType 6 "NO_OBJECT" 5 "OBJ_GUARDRAIL" 4 "OBJ_TUNNEL " 3 "OBJ_TRAFFIC_SIGN" 2 "OBJ_VEHICLE" 1 "OBJ_BRIDGE " 0 "OBJ_UNKNOWN" ; +VAL_TABLE_ VpathMode 2 "Mid Hi Spped" 1 "Low Speed" 0 "Disabled" ; +VAL_TABLE_ LaneChngStatus 2 "Lane Change Right" 1 "Lane Change Left" 0 "Idle" ; +VAL_TABLE_ TravelDirection 3 "Other (excessive side slip)" 2 "reverse / stopped in rvrs gear" 1 "Forward / stopped in frwd gear" 0 "Unknown" ; +VAL_TABLE_ TrueOrFalse 1 "true" 0 "false" ; +VAL_TABLE_ ModeCommand 5 "Sensing with Reduced Power" 4 "Undefined" 3 "Radio Silent" 2 "Sensing" 1 "Not Sensing" 0 "Undefined" ; +VAL_TABLE_ LaneSnsLLnPosValid 1 "Invalid" 0 "Valid" ; +VAL_TABLE_ LnSnsRLnPosValid 1 "Invalid" 0 "Valid" ; +VAL_TABLE_ Elevation 3 "Low " 2 "mid (reserved)" 1 "high " 0 "Unknown" ; +VAL_TABLE_ ModeCommandFdbk 5 "Sensing with reduced power" 4 "Undefined" 3 "Radio Silent" 2 "Sensing" 1 "Not Sensing" 0 "Undefined" ; +VAL_TABLE_ relativeLane 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ RoadTypeInfo 5 "Constiction Zone Exit" 4 "Construction Zone Entry" 3 "Highway" 2 "Secondary Road" 1 "City" 0 "Unknown" ; +VAL_TABLE_ ObjectLossInfo 2 "elevation conditions" 1 "tight curve" 0 "not lost" ; +VAL_TABLE_ MeasurementStatus 3 "Measured this cycle" 2 "Latent track not detctd this cyc" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ ObjectType 7 "no object present" 6 "fixed roadside object" 5 "fixed overhead object" 4 "pedestrian" 3 "motocycle / bicycle" 2 "Large vehicle (semi)" 1 "4 Wheel Vehicle (car, small trk)" 0 "Unknown" ; +VAL_TABLE_ Confidence 3 "confident" 2 "speculative" 1 "highly speculative" 0 "invalid" ; +VAL_TABLE_ DynamicProp 4 "Moving in opposite direction" 3 "Moving in same direction as host" 2 "Has moved but currently stopped" 1 "Has never moved" 0 "Unknown" ; +VAL_TABLE_ DrvWndPosSt 6 "Fully Opened" 5 "Open More Than C" 4 "Position C" 3 "Posistion B" 2 "Posistion A" 1 "Open Less Than A" 0 "Fully Closed" ; +VAL_TABLE_ VehMovSta 4 "Invalid" 3 "Reverse" 2 "Forward" 1 "Neutral" 0 "Parked" ; +VAL_TABLE_ OtsdAmbtLtLvlStat 2 "Day" 1 "Night" 0 "Unknown" ; +VAL_TABLE_ RtTrnLmpAtv 2 "On with telltale" 1 "On without telltale" 0 "Off" ; +VAL_TABLE_ LftTrnLmpAtv 2 "On with telltale" 1 "On without telltale" 0 "Off" ; +VAL_TABLE_ HdlmpBmSelectStat 2 "High Beams" 1 "Low Beams" 0 "Unknown" ; +VAL_TABLE_ DTCI_DTCFaultType 3 "Type C" 2 "Type B" 1 "Type A" 0 "Not Supported" ; +VAL_TABLE_ TrnsShftLvrPos 13 "Forward Range J" 12 "Froward Range I" 15 "Lever Position Unknown" 11 "Forward Range H" 10 "Forward Range G" 9 "Forward Range F" 8 "Forward Range E" 7 "Forward Range D" 6 "Forward Range C" 5 "Forward Range B" 4 "Forward Range A" 3 "Neutral Range" 2 "Reverse Range" 1 "Park Range" 0 "Between Ranges" ; +VAL_TABLE_ SysPwrMd 3 "Crank Request" 2 "Run" 1 "Accessory" 0 "Off" ; +VAL_TABLE_ ValidityStates 1 "Invalid" 0 "Valid" ; + + +BO_ 1548 ADAS_Profile_Short2_FO: 8 AMM_FO + SG_ AdvDrvAstMpPrfShrt2Val1 : 1|10@0+ (1,0) [0|1023] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Val0 : 33|10@0+ (1,0) [0|1023] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Updt : 39|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2RTrns : 3|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Typ : 38|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2PthIdx : 23|6@0+ (1,0) [0|63] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Ofst : 52|13@0+ (1,0) [0|8191] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2MsgTp : 55|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Dist1 : 17|10@0+ (1,0) [0|1023] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2CycCnt : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2CtlPt : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Acur : 5|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1547 ADAS_Profile_Long2_FO: 8 AMM_FO + SG_ AdvDrAstMpProfLng2Val : 39|32@0+ (1,0) [0|4294967295] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2Updt : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2RTrns : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2PrfTyp : 4|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2PthIdx : 13|6@0+ (1,0) [0|63] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2Ofst : 20|13@0+ (1,0) [0|8191] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2MgTyp : 23|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2CycCt : 15|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2CtrlPt : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1630 USDT_Resp_From_EOCM2B_K2_FO: 8 EOCM2B_K2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1374 UUDT_Resp_From_EOCM2B_K2_FO: 8 EOCM2B_K2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 606 USDT_Req_to_EOCM2B_K2_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2B_K2_FO + +BO_ 328 Vehicle_Info_FO: 5 EOCM2A_K1_FO + SG_ StrWhAngGrd : 27|12@0- (1,0) [-2048|2047] "deg/sec" DMS_FO + SG_ TrnsShftLvrPos : 31|4@0+ (1,0) [0|15] "" DMS_FO + SG_ StrWhAng_148 : 15|16@0- (0.0625,0) [-2048|2047.9375] "deg" DMS_FO + SG_ TrnsShftLvrPosV : 3|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngV_148 : 4|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngMsk_148 : 5|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngGrdV : 6|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngGrdMsk : 7|1@0+ (1,0) [0|1] "" DMS_FO + +BO_ 1930 DTC_Triggered_78A_FO: 7 LRSRR_FO + SG_ DTCI_CodeSupported_78A : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_78A : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_78A : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_78A : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_78A : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_78A : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_78A : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_78A : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_78A : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_78A : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_78A : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_78A : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_78A : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_78A : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_78A : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_78A : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_78A : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_78A : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_78A : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_78A : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1624 USDT_Resp_From_LRSRR: 8 LRSRR_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1368 UUDT_Resp_From_LRSRR: 8 LRSRR_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 600 USDT_Req_to_LRSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LRSRR_FO + +BO_ 613 PPS_QualMetrics_FO: 8 EOCM2A_K1_FO + SG_ PPSPstnDilPrcs : 47|10@0+ (0.1,0) [0|102.3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSMd : 53|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS3DAbsPosErrEstmt : 9|10@0+ (0.1,0) [0|102.3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsHdngErrEstmt : 0|7@0+ (0.5,0) [0|63.5] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsVelErrEstmt : 30|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSPosQltyMtrcsChksm : 50|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS2DAbsPosErrEstmt : 25|10@0+ (0.1,0) [0|102.3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSPosQltyMtcBrstID : 2|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS2DAbsPosErrEstmtV : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS3DAbsPosErrEstmtV : 4|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsHdngErrEstmtV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsVelErrEstmtV : 31|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSMdV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSPstnDilPrcsV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 612 PPS_Time_FO: 8 EOCM2A_K1_FO + SG_ PPSTmdayV : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrDayV : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrDay : 8|9@0+ (1,0) [0|511] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSTmBrstID : 52|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSTmday : 31|27@0+ (1,0) [0|134217727] "ms" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSTmChksm : 50|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrYrV : 1|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrYr : 15|7@0+ (1,2014) [2014|2141] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 611 PPS_SigAcqTime_FO: 6 EOCM2A_K1_FO + SG_ PPSSigAqTmBrstID : 38|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSSigAcqTmV : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSSigAcqTm : 7|32@0+ (1,0) [0|4294967295] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSSigAqTmChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 610 PPS_PosLong_FO: 6 EOCM2A_K1_FO + SG_ PPSLongBrstID : 39|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLong : 6|31@0- (1,0) [-1073741824|1073741823] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLongV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLongChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 609 PPS_PosLat_FO: 6 EOCM2A_K1_FO + SG_ PPSLatV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLatChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLatBrstID : 36|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLat : 5|30@0- (1,0) [-536870912|536870911] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 1160 PassPhrase_3_AMM_FO: 8 EOCM2A_K1_FO + SG_ WiFiPssPhrsDgts17to24_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1159 PassPhrase_2_AMM_FO: 8 EOCM2A_K1_FO + SG_ WiFiPssPhrsDgts9to16_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1158 PassPhrase_1_AMM_FO: 8 EOCM2A_K1_FO + SG_ WiFiPssPhrsDgts1to8_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1546 ADAS_Protection_FO: 4 AMM_FO + SG_ AdvDrAstMpPrfLng2Avbl : 11|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPosAvbl : 15|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpHwFlt : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtAvbl : 8|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpProtChksm : 23|16@0+ (1,0) [0|65535] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpProtRTrns : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpProtCycCtMsg : 2|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbAvbl : 9|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpSegAvbl : 10|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfShrtAvbl : 14|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfShrt2Avbl : 13|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLngAvbl : 12|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpInpSigFld : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1545 ADAS_Metadata_FO: 8 AMM_FO + SG_ AdvDrAstMpMtdtVerYrQtr : 60|2@0+ (1,1) [1|4] "Qtr" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtVerYr : 53|6@0+ (1,2000) [2000|2063] "Year" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtSpdUnt : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtPrvdr : 7|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMsgTyp : 58|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMnrPrtVr : 23|4@0+ (1,0) [0|15] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtCycCnt : 18|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtRgnCd : 38|15@0+ (1,0) [0|32767] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtHwVer : 16|9@0+ (1,0) [0|511] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMnrPrtSbVr : 4|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMjrPrtVr : 55|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtDrvSd : 19|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtCntryCd : 1|10@0+ (1,0) [0|1023] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1543 ADAS_Profile_Long_FO: 8 AMM_FO + SG_ AdvDrAstMpPrfLngUpdt : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngRTrns : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngCtlPt : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngTyp : 4|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngCycCt : 15|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngPthIdx : 13|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngMsgTp : 23|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngOfst : 20|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngVal : 39|32@0+ (1,0) [0|4294967295] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1544 ADAS_Profile_Short_FO: 8 AMM_FO + SG_ AdvDrvAstMpPrfShrtVal1 : 1|10@0+ (1,0) [0|1023] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtVal0 : 33|10@0+ (1,0) [0|1023] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtDist1 : 17|10@0+ (1,0) [0|1023] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtCycCnt : 7|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtAcur : 5|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtCtlPt : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtRetr : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtTyp : 38|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtUpdt : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtPthIdx : 23|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtMsgTp : 55|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtOfst : 52|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1542 ADAS_Stub_FO: 8 AMM_FO + SG_ AdvDrAstMpStbSubPthIdx : 63|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbUpdt : 55|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbPrtCalRut : 57|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbNmLnDrvDir : 54|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbCycCnt : 51|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbCmplxInsct : 49|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbTrnAngl : 47|8@0+ (1.417,0) [0|361.335] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbRtOfWay : 38|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbRelProb : 36|5@0+ (3.333,0) [0|103.323] "%" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbRetr : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbNmLnOppDir : 31|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbPathIdx : 29|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbLstStbOfst : 23|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbMsgTyp : 22|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbFmOfWay : 19|4@0+ (1,0) [0|15] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbFuncRdCls : 7|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbOfst : 4|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1541 ADAS_Segment_FO: 8 AMM_FO + SG_ AdvDrAstMpSegRelProb : 12|5@0+ (3.333,0) [0|103.323] "%" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegUpdt : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegTunl : 25|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegCycCnt : 39|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegCmplxInsct : 37|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegBldUpAra : 43|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegBrdg : 41|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegRTrns : 1|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegDivdRd : 31|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegPthIdx : 7|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegPrtCalRut : 27|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegNmLnOppDir : 29|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegNmLnDrvDir : 55|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegMsgTyp : 46|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegFunRdCls : 23|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegFrmOfWay : 35|4@0+ (1,0) [0|15] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegEffSpdLmt : 20|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegEffSdLmtTp : 15|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegOffset : 52|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 608 PPS_ElevHdSpd_FO: 8 EOCM2A_K1_FO + SG_ PPSVel : 31|8@0+ (1,0) [0|255] "km / h" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSVelV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvHedngSpdBrstID : 5|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvHdengSpdChksm : 50|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSHedngV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSHedng : 2|19@0+ (0.001,0) [0|524.287] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvtnV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvtn : 39|21@0+ (1,-100000) [-100000|1997151] "cm" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 1168 WiFi_Station_AMM_FO: 5 AMM_FO + SG_ WSMR_WiFiStnMpMACAddr : 15|32@0+ (1,0) [0|4294967295] "" EOCM2B_K1_FO,EOCM2A_K1_FO + SG_ WSMR_WiFiAssnReq : 1|2@0+ (1,0) [0|3] "" EOCM2B_K1_FO,EOCM2A_K1_FO + +BO_ 1161 WiFi_AP_Data_AMM_FO: 2 EOCM2A_K1_FO + SG_ WAPDM_SecurityType : 15|4@0+ (1,0) [0|15] "" EOCM2B_K1_FO,AMM_FO + SG_ WAPDM_WiFiEnStat : 0|1@0+ (1,0) [0|1] "" EOCM2B_K1_FO,AMM_FO + SG_ WAPDM_EncrptnType : 11|4@0+ (1,0) [0|15] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1157 SSID_AMM_3_FO: 8 EOCM2A_K1_FO + SG_ WiFiSSIDDgts17to24_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 326 DMS_Eye_AOI_Info_FO: 6 DMS_FO + SG_ DrvrMontSysInit : 1|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMontSysAvlbl : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMontMdlDatFlshProgrs : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngRecvrFltCodARC : 36|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStat : 39|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatPrd : 22|15@0+ (0.025,0) [0|819.175] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngRecvrFltCodV : 23|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngUnrecvrFltCod : 10|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngUnrecvrFltCodV : 11|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatCnfdc : 13|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngRecvrFltCod : 15|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatV : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 324 DMS_RawMeasurement_Info2_FO: 8 DMS_FO + SG_ DrvrMonFrmNum : 47|8@0+ (1,0) [0|255] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMntrSysVTP : 29|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonSysEngStV : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonSysEngSt : 28|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonFrmNumV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngZV : 4|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngYV : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngXV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngARC : 52|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonLatV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonLat : 50|11@0+ (0.001,0) [0|2.047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadRotAngZ : 25|10@0- (0.00625,0) [-3.2|3.19375] "rad" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvHeadRotAngY : 23|10@0- (0.00625,0) [-3.2|3.19375] "rad" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvrHeadRotAngX : 1|10@0- (0.00625,0) [-3.2|3.19375] "rad" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 322 DMS_RawMeasurement_Info1_FO: 8 DMS_FO + SG_ DrvrEyeClosrRt : 47|8@0+ (0.005,0) [0|1.275] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrLft : 39|8@0+ (0.005,0) [0|1.275] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosZV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosYV : 4|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosXV : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrRtV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrLftV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrARC : 52|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosZ : 50|11@0- (0.005,0) [-5.12|5.115] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvHeadPosY : 18|11@0- (0.005,0) [-5.12|5.115] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvHeadPosX : 2|11@0- (0.005,0) [-5.12|5.115] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 320 Inertial2_Rates_FO: 8 _DOFIMU2_FO + SG_ MstrTgrSyncInrtl2Rte : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2YawRteV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2YawRte : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2RollRteV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2RollRte : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2RteChksum : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2PitchRteV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2PitchRte : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 308 Inertial1_Rates_FO: 8 _DOFIMU1_FO + SG_ MstrTrgrSyncInrtl1Rte : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1YawRteV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1YawRte : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1RollRteV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1RollRte : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1RteChksum : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1PitchRteV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1PitchRte : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 312 Inertial2_Accel2_FO: 8 _DOFIMU2_FO + SG_ MstrTrigSyncInrtl22 : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSns2AccFrm2Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2YawAccV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2YawAcc : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2RollAccV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2RollAcc : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2PtchAccV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2PtchAcc : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 306 Inertial1_Accel2_FO: 8 _DOFIMU1_FO + SG_ MstrTrigSyncInrtl12 : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1AccelFrm2Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1YawAccV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1YawAcc : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1RollAccV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1RollAcc : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1PtchAccV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1PtchAcc : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 310 Inertial2_Accel1_FO: 8 _DOFIMU2_FO + SG_ MstrTrigSyncInrtl21 : 7|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2VertAccV : 34|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2VertAcc : 33|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LonAccV : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LonAcc : 1|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LatAccV : 18|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LatAcc : 17|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ IntlSnsr2AcelFm1Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 304 Inertial1_Accel1_FO: 8 _DOFIMU1_FO + SG_ MstrTrigSyncInrtl11 : 7|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1VertAccV : 34|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1VertAcc : 33|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LonAccV : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LonAcc : 1|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LatAccV : 18|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LatAcc : 17|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ IntlSnsr1AcelFm1Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 356 Map_Pos_Correction_FO: 4 EOCM2A_K1_FO + SG_ LongErrPstn : 7|8@0- (0.5,0) [-64|63.5] "m" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ LatErrPstn : 15|8@0- (0.5,0) [-64|63.5] "m" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ PstnErrChcksm : 18|11@0+ (1,0) [0|2047] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ PstnErrARC : 20|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 354 Map_Retrans_Request_FO: 1 EOCM2A_K1_FO + SG_ HrznPrvdRstRq : 2|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ADASISRwDtMplxdCycCnt : 7|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ADASISMsgTypRetrans : 5|3@0+ (1,0) [0|7] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 352 Map_Path_Correction_FO: 6 EOCM2A_K1_FO + SG_ ExptNxtTrnstnDir : 37|3@0+ (1,0) [0|7] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ MstProbLnV : 15|1@0+ (1,0) [0|1] "" AMM_FO + SG_ MstProbLn : 14|5@0+ (1,0) [0|31] "" AMM_FO + SG_ PathCrtnChcksm : 34|11@0+ (1,0) [0|2047] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ PathCrtnARC : 4|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ EgoLnCurvV : 2|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ EgoLnCurv : 23|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m^2" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ VehLnStatV : 1|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ VehLnStatConf : 6|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ VehLnStat : 9|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ExptNxtTransDirV : 0|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ExptNxtTrnstnDirConf : 39|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 264 Inertial_Trigger_FO: 1 EOCM2A_K1_FO + SG_ InrtlSnsrMstrTrgrSync : 7|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,_DOFIMU2_FO,_DOFIMU1_FO + +BO_ 1156 SSID_AMM_2_FO: 8 EOCM2A_K1_FO + SG_ WiFiSSIDDgts9to16_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1155 SSID_AMM_1_FO: 8 EOCM2A_K1_FO + SG_ WiFiSSIDDgts1to8_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1927 DTC_Triggered_787_FO: 7 DMS_FO + SG_ DTCI_CodeSupported_787 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_787 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_787 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_787 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_787 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_787 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_787 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_787 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_787 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_787 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_787 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_787 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_787 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_787 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_787 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_787 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_787 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_787 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_787 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_787 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1926 DTC_Triggered_786_FO: 7 AMM_FO + SG_ DTCI_CodeSupported_786 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_786 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_786 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_786 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_786 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_786 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_786 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_786 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_786 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_786 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_786 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_786 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_786 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_786 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_786 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_786 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_786 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_786 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_786 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_786 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1928 DTC_Triggered_788_FO: 7 _DOFIMU1_FO + SG_ DTCI_CodeSupported_788 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_788 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_788 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_788 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_788 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_788 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_788 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_788 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_788 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_788 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_788 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_788 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_788 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_788 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_788 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_788 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_788 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_788 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_788 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_788 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1929 DTC_Triggered_789_FO: 7 _DOFIMU2_FO + SG_ DTCI_CodeSupported_789 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_789 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_789 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_789 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_789 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_789 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_789 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_789 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_789 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_789 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_789 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_789 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_789 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_789 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_789 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_789 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_789 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_789 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_789 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_789 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1352 UUDT_Resp_From_6DOFIMU2_FO: 8 _DOFIMU2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 588 USDT_Req_to_EOCM2B_K1_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2B_K1_FO + +BO_ 1356 UUDT_Resp_From_EOCM2B_K1_FO: 8 EOCM2B_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1612 USDT_Resp_From_EOCM2B_K1_FO: 8 EOCM2B_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1616 USDT_Resp_From_EOCM2A_IMX6_FO: 8 EOCM2A_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1360 UUDT_Resp_From_EOCM2A_IMX6_FO: 8 EOCM2A_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 592 USDT_Req_to_EOCM2A_IMX6_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2A_IMX6_FO + +BO_ 1610 USDT_Resp_From_EOCM2A_K1_FO: 8 EOCM2A_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1354 UUDT_Resp_From_EOCM2A_K1_FO: 8 EOCM2A_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 586 USDT_Req_to_EOCM2A_K1_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2A_K1_FO + +BO_ 1925 DTC_Triggered_785_FO: 7 NVS_FO + SG_ DTCI_CodeSupported_785 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_785 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_785 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_785 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_785 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_785 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_785 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_785 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_785 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_785 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_785 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_785 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_785 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_785 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_785 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_785 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_785 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_785 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_785 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_785 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1859 VIN_Digits_10_to_17_FO: 8 EOCM_F_FO + SG_ VehIdNmDig10_17 : 7|64@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + +BO_ 1857 VIN_Digits_2_to_9_FO: 8 EOCM_F_FO + SG_ VehIdNmDig2_9 : 7|64@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + +BO_ 771 Outside_Air_Temperature_FO: 2 EOCM_F_FO + SG_ OtsAirTmpCrValV : 0|1@0+ (1,0) [0|1] "" NVS_FO + SG_ OtsAirTmpCrVal : 15|8@0+ (0.5,-40) [-40|87.5] "deg C" NVS_FO + +BO_ 777 Night_Vision_System_Ped_FO: 1 NVS_FO + SG_ NVSysStat : 3|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ NVSysPedWrnIndReq : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ NVSysPedDetCsCrStVal : 5|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ NVSysPedDetCstStAvl : 0|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 607 USDT_Req_to_NVS_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" NVS_FO + +BO_ 1631 USDT_Resp_From_NVS_FO: 8 NVS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1375 UUDT_Resp_From_NVS_FO: 8 NVS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1540 ADAS_Position_FO: 8 AMM_FO + SG_ AdvDrAstMpLatOffst : 40|9@0+ (1,-256) [-256|255] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnIndx : 63|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnCnf : 61|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPsnIdxCrLn : 58|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnPthIndx : 46|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnProb : 31|5@0+ (3.333,0) [0|103.323] "%" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnCycCnt : 26|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnAge : 24|9@0+ (5,0) [0|2555] "ms" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnRelHd : 23|8@0+ (1.417,0) [0|361.335] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnMsgTyp : 7|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnOfst : 4|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1608 USDT_Resp_From_6DOFIMU2_FO: 8 _DOFIMU2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 871 LGT_ObjectDetect_Info_8_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk8 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk8 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk8 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk8 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev8 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev8 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev8 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk8 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk8 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk8 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 870 LGT_ObjectDetect_Info_7_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk7 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk7 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk7 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk7 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev7 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev7 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev7 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk7 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk7 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk7 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 869 LGT_ObjectDetect_Info_6_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk6 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk6 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk6 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk6 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev6 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev6 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev6 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk6 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk6 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk6 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 868 LGT_ObjectDetect_Info_5_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk5 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk5 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk5 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk5 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev5 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev5 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev5 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk5 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk5 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk5 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 867 LGT_ObjectDetect_Info_4_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk4 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk4 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk4 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk4 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev4 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev4 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev4 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk4 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk4 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk4 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 866 LGT_ObjectDetect_Info_3_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk3 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk3 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk3 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk3 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev3 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev3 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev3 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk3 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk3 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk3 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 865 LGT_ObjectDetect_Info_2_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk2 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk2 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk2 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk2 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev2 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev2 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev2 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk2 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBObjDirTrk2 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk2 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 864 LGT_ObjectDetect_Info_1_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk1 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk1 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk1 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk1 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev1 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev1 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev1 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk1 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk1 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk1 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1915 DTC_Triggered_77B_FO: 7 VIS_FO + SG_ DTCI_DTCFaultType_77B : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CodeSupported_77B : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_77B : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_77B : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_77B : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_77B : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_77B : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_77B : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_77B : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_77B : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_77B : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_77B : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_77B : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_77B : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_77B : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_77B : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_77B : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_77B : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_77B : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_77B : 7|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1923 DTC_Triggered_783_FO: 7 RSRR_FO + SG_ DTCI_WrnIndRqdSt_783 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_783 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_783 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_783 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_783 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_783 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_783 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_783 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_783 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_783 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_783 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CurrentStatus_783 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CodeSupported_783 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_783 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_783 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_783 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_783 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_783 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_783 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_783 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1924 DTC_Triggered_784_FO: 7 RRSRR_FO + SG_ DTCI_HistStat_784 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_784 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_784 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_784 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_784 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_784 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_784 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_784 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_784 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_784 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_784 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_784 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_784 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CodeSupported_784 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_784 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_784 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_784 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_784 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_784 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_784 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1922 DTC_Triggered_782_FO: 7 RFSRR_FO + SG_ DTCI_WrnIndRqdSt_782 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_782 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_782 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_782 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_782 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_782 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_782 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_782 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_782 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_782 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_782 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_782 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_782 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_782 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_782 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_782 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_782 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_782 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CurrentStatus_782 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CodeSupported_782 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1920 DTC_Triggered_780_FO: 7 LRR_FO + SG_ DTCI_CurrentStatus_780 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_780 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_780 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_780 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_780 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_780 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_780 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_780 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_780 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_780 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_780 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_780 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_780 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_780 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_780 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_780 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_780 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_780 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_780 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CodeSupported_780 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1921 DTC_Triggered_781_FO: 7 LFSRR_FO + SG_ DTCI_CurrentStatus_781 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_781 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_781 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_781 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_781 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_781 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_781 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_781 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_781 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_781 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_781 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_781 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_781 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_781 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_781 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_781 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_781 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_781 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_781 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CodeSupported_781 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1034 Curvature_Right_Line_FO: 7 VIS2_FO + SG_ CRL_Cnfdnc : 50|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CRL_ViewRng : 33|15@0+ (0.0039064,0) [0|128.0010088] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CRL_CoefdA : 17|16@0- (3.6622E-009,0) [-0.0001200029696|0.0001199993074] "1/m^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CRL_CoefA : 1|16@0- (6.1036E-007,0) [-0.02000027648|0.01999966612] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1033 Curvature_Left_Line_FO: 7 VIS2_FO + SG_ CLL_Cnfdnc : 50|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CLL_ViewRng : 33|15@0+ (0.0039064,0) [0|128.0010088] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CLL_CoefdA : 17|16@0- (3.6622E-009,0) [-0.0001200029696|0.0001199993074] "1/m^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CLL_CoefA : 1|16@0- (6.1036E-007,0) [-0.02000027648|0.01999966612] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1365 UUDT_Resp_From_VIS2_FO: 8 VIS2_FO + SG_ DgnInf_OBJ555 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1621 USDT_Resp_From_VIS2_FO: 8 VIS2_FO + SG_ DgnInf_OBJ655 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1094 F_Vision_Obj_Track_12: 8 VIS2_FO + SG_ FwdVsnObjTypTr12Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk12Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk12Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FVisionWidthTrk12 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FVisionMeasStatTrk12 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk12 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisionRelLaneTrk12 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk12 : 34|11@0- (0.125,0) [-128|127.875] "deg/sec" EOCM_F_FO + SG_ FVisionConfTrk12 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ ObjDirTrk12 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk12 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk12 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1093 F_Vision_Obj_Track_11: 8 VIS2_FO + SG_ FwdVsnObjTypTr11Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk11Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk11Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FVisionWidthTrk11 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FVisionMeasStatTrk11 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk11 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisionRelLaneTrk11 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk11 : 34|11@0- (0.125,0) [-128|127.875] "deg/sec" EOCM_F_FO + SG_ FVisionConfTrk11 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ ObjDirTrk11 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk11 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk11 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1100 F_Vision_Obj_Track_12_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT12Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk12 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk12 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk12 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk12 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr12 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk12 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo12 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1099 F_Vision_Obj_Track_11_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT11Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk11 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk11 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk11 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk11 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr11 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk11 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo11 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1098 F_Vision_Obj_Track_10_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT10Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk10 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk10 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk10 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk10 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr10 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk10 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo10 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1097 F_Vision_Obj_Track_9_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT9Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk9 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk9 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk9 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk9 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr9 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk9 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo9 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1096 F_Vision_Obj_Track_8_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT8Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk8 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk8 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk8 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk8 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr8 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk8 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo8 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1095 F_Vision_Obj_Track_7_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT7Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk7 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk7 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk7 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk7 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr7 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk7 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo7 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 863 F_Vision_GFHB_Data_FO: 8 VIS2_FO + SG_ RgDtLgtSrcHrtAngl : 49|10@0- (0.04,0) [-20.48|20.44] "deg" EOCM_F_FO + SG_ RgDtLgtSrcHrtAngVcty : 55|6@0- (1,0) [-32|31] "deg/sec" EOCM_F_FO + SG_ LfDtLgtSrcHrtAngl : 33|10@0- (0.04,0) [-20.48|20.44] "deg" EOCM_F_FO + SG_ LfDtLgtSrcHrtAnVcty : 39|6@0- (1,0) [-32|31] "deg/sec" EOCM_F_FO + SG_ AdvWthrStat : 25|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ DtctdLghtSrcDstnc : 22|7@0+ (10,0) [0|1270] "m" EOCM_F_FO + SG_ DtctdLghtSrcVrtclAngl : 1|10@0- (0.04,0) [-20.48|20.44] "deg" EOCM_F_FO + SG_ IntLghtRngAct : 2|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ DtctdLghtSrcDstncV : 3|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ TwnDtctnSts : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ DtctdLghtSrcDrvngDrctn : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 862 LGT_ControlHighBeamGlare_FO: 2 VIS2_FO + SG_ FwdCamSysOpStat : 10|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ EnvIllum : 2|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RdTyp : 5|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ AutoHgBmSts : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1068 F_Vision_Obj_Track_6_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT6Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk6 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk6 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk6 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk6 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr6 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk6 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo6 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1067 F_Vision_Obj_Track_5_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT5Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk5 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk5 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk5 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk5 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr5 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk5 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo5 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1066 F_Vision_Obj_Track_4_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT4Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk4 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk4 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk4 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk4 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr4 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk4 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo4 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1065 F_Vision_Obj_Track_3_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT3Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk3 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk3 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk3 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk3 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr3 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk3 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo3 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1064 F_Vision_Obj_Track_2_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT2Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk2 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk2 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk2 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk2 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr2 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk2 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo2 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1063 F_Vision_Obj_Track_1_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT1Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk1 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FwdVsnObjAgeTrk1 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk1 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk1 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk1 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr1 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo1 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1151 Long_Range_Radar_add_Info_5_FO: 8 LRR_FO + SG_ FrtRdrRdEdgLtLatRdEdgDst : 63|8@0- (0.1,0) [-12.8|12.7] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtPrvDst : 5|4@0+ (10,0) [0|150] "" EOCM_F_FO + SG_ FrtRdrRdEdgLtTanHdgAng : 15|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtV : 48|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtGradV : 0|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtGrad : 39|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtConf : 55|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvt : 23|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM_F_FO + SG_ FrtRdrRdEdgLtTanHdgAngV : 1|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAddInfo5BurstID : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1150 Long_Range_Radar_add_Info_4_FO: 8 LRR_FO + SG_ FrtRdrRdEdgRtLatRdEdgDst : 63|8@0- (0.1,0) [-12.8|12.7] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtPrvDst : 5|4@0+ (10,0) [0|150] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtTanHdgAngV : 1|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtTanHdgAng : 15|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtV : 48|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtGradV : 0|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtGrad : 39|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtConf : 55|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvt : 23|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM_F_FO + SG_ FLRRAddInfo4BurstID : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1088 F_Vision_Obj_Header_2: 8 VIS2_FO + SG_ FrntVsnInPthVehBrkNwSt : 35|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FrntVsnClostPedBrkNwSt : 39|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FrntVsnClostPedObjID : 29|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FrntVsnClostPedAlrtNwFlg : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrntVsnClostPedNotftnFlg : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrntVsnInPthVehAlrtNwFlg : 2|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnVldTgtNum2 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FrtVsnTmStmp2V : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnTmStmp2 : 10|11@0+ (1,0) [0|2047] "" EOCM_F_FO + SG_ FrtVsnRollCnt2 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FrtVsnBrstChksum2 : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + +BO_ 854 F_Vision_Environment_7: 3 VIS2_FO + SG_ FwdVsnCnstrctAreaDst : 13|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnCnstrctZnDet : 15|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnEgoVehLnPos : 17|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnRdTypDet : 9|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnTunnlDetd : 23|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnTunnlDst : 21|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBrstID5 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 853 F_Vision_Environment_6: 8 VIS2_FO + SG_ LnMrkg4LnSnsLnHdngTngtV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnHdngTngt : 23|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnDstV : 56|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnDst : 15|8@0- (0.1,0) [-12.8|12.7] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvtV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvtGradV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvtGrad : 47|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvt : 31|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnQltyConfLvl : 63|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMrkrTyp : 4|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBrstID4 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 852 F_Vision_Environment_5: 8 VIS2_FO + SG_ LnMrkg3LnSnsLnHdngTngtV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnHdngTngt : 23|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnDstV : 56|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnDst : 15|8@0- (0.1,0) [-12.8|12.7] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvtV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvtGradV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvtGrad : 47|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvt : 31|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnQltyConfLvl : 63|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMrkrTyp : 4|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBrstID3 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 602 USDT_Req_to_RRSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RRSRR_FO + +BO_ 1626 USDT_Resp_From_RRSRR: 8 RRSRR_FO + SG_ DgnInf_OBJ65A : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1370 UUDT_Resp_From_RRSRR: 8 RRSRR_FO + SG_ DgnInf_OBJ55A : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1536 RR_SRR_Trace_data: 8 RRSRR_FO + SG_ RRSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RRSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RRSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 1210 RR_SRR_Object_Track10: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1209 RR_SRR_Object_Track9: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1208 RR_SRR_Object_Track8: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1207 RR_SRR_Object_Track7: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1206 RR_SRR_Object_Track6: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1205 RR_SRR_Object_Track5: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 262 LHT_AutoHighBeamAssistStatus_FO: 5 EOCM_F_FO + SG_ NtVsnSysEnbld : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + SG_ VehMovState : 5|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + SG_ NVSysPedDetCstReq : 2|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + SG_ StrWhAngV : 8|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO,VIS_FO + SG_ StrWhAngMsk : 9|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ StrWhAng : 23|16@0- (0.0625,0) [-2048|2047.9375] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO,VIS_FO + SG_ RtTrnLmpAtv : 13|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ MpDataAvlbl : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ LftTrnLmpAtv : 11|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ HdlmpBmSelectStat : 33|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ BldUpArDet : 14|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ FrFogLmpsAct : 15|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO,VIS_FO + +BO_ 309 LHT_CameraObjConfirmation_FO: 1 VIS_FO + SG_ HiBmRecmnd : 1|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ CtLghtDet : 0|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 2034 CCP_Data_Transmission_Object_FO: 8 VIS2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 2032 CCP_Command_Receive_Object_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" VIS2_FO + +BO_ 1362 F_Vis_Obj_Conf_CPS_1B: 8 EOCM_F_FO + SG_ FObjConfCPSTrkObjectIDB : 7|6@0+ (1,0) [0|63] "" VIS_FO + SG_ CPSVisConfLonPos1 : 20|12@0- (0.125,0) [-256|255.875] "m" VIS_FO + SG_ CPSVisConfLatPos1 : 15|10@0- (0.125,0) [-64|63.875] "m" VIS_FO + SG_ CPSVisConfChecksum : 50|11@0+ (1,0) [0|2047] "" VIS_FO + SG_ FObjConfCPSTrkRangeRate : 45|11@0- (0.125,0) [-128|127.875] "m/s" VIS_FO + SG_ CPSConfTimeStamp : 24|11@0+ (1,0) [0|2047] "ms" VIS_FO + SG_ CPSConfTimeStampV : 21|1@0+ (1,0) [0|1] "" VIS_FO + SG_ FObjConfCPSRollingTrkCnt : 1|2@0+ (1,0) [0|3] "" VIS_FO + +BO_ 1413 TOS_ACC_IDS: 5 EOCM_F_FO + SG_ TOS_ACC_IDSRollCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ TOS_ACC_IDSFuncState : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ TOS_ACC_ID1 : 3|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID2 : 13|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID3 : 23|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID4 : 17|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID5 : 27|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID6 : 37|6@0+ (1,0) [0|63] "" Dummy_FO + +BO_ 1412 F_ACC_Target: 8 EOCM_F_FO + SG_ FACCTOSRollCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSFuncState : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSLongPos : 3|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FACCTOSLatPos : 23|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FACCTOSMeasStat : 28|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSLongVel : 26|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FACCTOSTrgtDecelFlg : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FACCTOSDynProp : 46|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FACCTOSLatVel : 42|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FACCTOSRelLane : 63|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSHiThrtID : 61|6@0+ (1,0) [0|63] "" Dummy_FO + +BO_ 1409 F_CPS_TOS_B: 8 EOCM_F_FO + SG_ CPSTOSObjType : 7|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ CPSTOSHiThrtPriNo : 60|5@0+ (1,0) [0|31] "" Dummy_FO + SG_ CPSTOSRelLongAcc : 53|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ CPSTOSConfAsmt : 21|12@0+ (1,0) [0|4095] "" Dummy_FO + SG_ CPSTOSNumCycTrkd : 4|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ CPSTOSTimeToColl : 1|12@0+ (0.025,0) [0|102.375] "s" Dummy_FO + SG_ CPSTOSClosestInPthVehRng : 47|10@0+ (0.25,0) [0|255.75] "m" Dummy_FO + SG_ CPSTOSClosestInPthObID : 37|6@0+ (1,0) [0|63] "m" Dummy_FO + SG_ CPSTOSMeasStat : 39|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ CPSTOSFuncState : 25|2@0+ (1,0) [0|3] "" Dummy_FO + +BO_ 1408 F_CPS_TOS_A: 8 EOCM_F_FO + SG_ CPSTOSLongPos : 7|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ CPSTOSLatPos : 11|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ CPSTOSLongVel : 16|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ CPSTOSDynProp : 37|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ CPSTOSLatVel : 34|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ CPSTOSARelLane : 63|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ CPSTOSHiThrtID : 61|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ CPSTOSHighestThreatObAsmt : 55|8@0+ (1,0) [0|255] "" Dummy_FO + +BO_ 1344 FLPEstimate: 8 EOCM_F_FO + SG_ FLPRollCount : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ NewLaneIndex : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ VehPathInOK : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LaneSnsInOK : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ MapInOK : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FWDObjFusInOK : 0|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LngthFrstSeg : 15|4@0+ (10,0) [0|150] "m" Dummy_FO + SG_ LngthScndSeg : 11|4@0+ (10,0) [0|150] "m" Dummy_FO + SG_ CurvFrstSeg : 23|13@0- (5E-005,0) [-0.2048|0.20475] "1/m" Dummy_FO + SG_ CurvScndSeg : 26|3@0- (0.001,0) [-0.004|0.003] "1/m" Dummy_FO + SG_ OffstLaneCntr : 39|8@0- (0.05,0) [-6.4|6.35] "m" Dummy_FO + SG_ TngntLaneHead : 47|8@0- (0.002,0) [-0.256|0.254] "m/m" Dummy_FO + SG_ LaneWidth : 55|8@0+ (0.05,0) [0|12.75] "m" Dummy_FO + SG_ FLPDataTimeStampV : 63|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FLPDataTimeStamp : 62|7@0+ (16,0) [0|2032] "ms" Dummy_FO + +BO_ 770 F_Fwd_Collision_Alert: 8 EOCM_F_FO + SG_ Vpath_Accel : 51|11@0- (0.125,0) [-128|127.875] "m/s^2" NVS_FO,Dummy_FO + SG_ FCA_Ra : 7|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FCA_Range : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FCA_AlertLevel : 44|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FCA_Alert_Sup : 31|16@0+ (1,0) [0|65535] "" Dummy_FO + SG_ FCAStatus : 46|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FCA_VehAhead : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCA_CPS_Alert : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCAChime : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCADiagOK : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ NBSMS_Alert : 55|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1601 USDT_Resp_From_VIS: 8 VIS_FO + SG_ DgnInf_OBJ641 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1606 USDT_Resp_From_RFSRR: 8 RFSRR_FO + SG_ DgnInf_OBJ646 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1603 USDT_Resp_From_LFSRR: 8 LFSRR_FO + SG_ DgnInf_OBJ643 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1602 USDT_Resp_From_LRR: 8 LRR_FO + SG_ DgnInf_OBJ642 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1625 USDT_Resp_From_RSRR: 8 RSRR_FO + SG_ DgnInf_OBJ644 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1611 USDT_Resp_From_FEOCM_FO: 8 EOCM_F_FO + SG_ DgnInf_OBJ64B : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 768 F_Smgr_Vehicle_Motion: 8 EOCM_F_FO + SG_ SmgrMotRollAngle : 44|10@0- (0.1,0) [-51.2|51.1] "deg" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotRollAngleV : 0|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotChecksum : 50|11@0+ (1,0) [0|2047] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotPitchAngle : 39|11@0- (0.1,0) [-102.4|102.3] "deg" CIPM_FO,NVS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotPitchAngleV : 1|1@0+ (1,0) [0|1] "" CIPM_FO,NVS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotLongSpeedV : 2|1@0+ (1,0) [0|1] " " CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotLongSpeed : 18|11@0- (0.1,0) [-102.4|102.3] "m/s" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotYawRate : 14|12@0- (0.05,0) [-102.4|102.35] "deg/s" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotYawRateV : 15|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotRollingCnt : 4|2@0+ (1,0) [0|3] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + +BO_ 1350 UUDT_Resp_From_RFSRR: 8 RFSRR_FO + SG_ DgnInf_OBJ546 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1369 UUDT_Resp_From_RSRR: 8 RSRR_FO + SG_ DgnInf_OBJ544 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1347 UUDT_Resp_From_LFSRR: 8 LFSRR_FO + SG_ DgnInf_OBJ543 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1346 UUDT_Resp_From_LRR: 8 LRR_FO + SG_ DgnInf_OBJ542 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1345 UUDT_Resp_From_VIS: 8 VIS_FO + SG_ DgnInf_OBJ541 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 579 USDT_Req_to_LFSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LFSRR_FO + +BO_ 577 USDT_Req_to_VIS: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" VIS_FO + +BO_ 578 USDT_Req_to_LRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LRR_FO + +BO_ 582 USDT_Req_to_RFSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RFSRR_FO + +BO_ 601 USDT_Req_to_RSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RSRR_FO + +BO_ 1355 UUDT_Resp_From_FEOCM_FO: 8 EOCM_F_FO + SG_ DgnInf_OBJ54B : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 587 USDT_Req_to_FEOCM_obj: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2A_K2_FO,EOCM_F_FO + +BO_ 784 Body_Info_FOB: 6 EOCM_F_FO + SG_ StrgColUpDwnPos : 39|8@0+ (1,0) [0|255] "" DMS_FO + SG_ CPMAPINFO4 : 47|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrgColInOutPos : 31|8@0+ (1,0) [0|255] "" DMS_FO + SG_ StrgColCommsFlt : 19|2@0+ (1,0) [0|3] "" DMS_FO + SG_ DrDoorOpenSwActV : 16|1@0+ (1,0) [0|1] "" DMS_FO + SG_ DrDoorOpenSwAct : 17|1@0+ (1,0) [0|1] "" DMS_FO + SG_ DrvWndPosStat : 22|3@0+ (1,0) [0|7] "" CIPM_FO,DMS_FO,VIS2_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InterLghtStat : 23|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,VIS2_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvrHndsOnWhlZn3 : 13|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,DMS_FO,VIS2_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvrHndsOnWhlZn2 : 14|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,VIS2_FO + SG_ DrvrHndsOnWhlZn1 : 15|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,VIS2_FO + SG_ WSWshSwAtv : 11|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,VIS_FO,VIS2_FO + SG_ SysPwrMdV : 8|1@0+ (1,0) [0|1] "" NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO,LRSRR_FO,CIPM_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,VIS2_FO + SG_ SysPwrMd : 10|2@0+ (1,0) [0|3] "" NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO,LRSRR_FO,CIPM_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,VIS2_FO + SG_ WSWprAct : 2|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ RtLwBmFld : 4|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ OtsdAmbtLtLvlStatV : 5|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ OtsdAmbtLtLvlStat : 7|2@0+ (1,0) [0|3] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ LowBmAct : 1|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ LftLwBmFld : 3|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ HighBmAct : 0|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ TrStLgMdAtv : 12|1@0+ (1,0) [0|1] "" CIPM_FO,NVS_FO,RRSRR_FO,LRSRR_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,LRR_FO,RFSRR_FO,LFSRR_FO,RSRR_FO,VIS_FO,VIS2_FO + +BO_ 1539 RF_SRR_Trace_Data: 8 RFSRR_FO + SG_ RFSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RFSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RFSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 776 F_Vehicle_Path_Data_2: 7 EOCM_F_FO + SG_ Vpath_Data2ModeInfo : 44|2@0+ (1,0) [0|3] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath2_Checksum : 42|11@0+ (1,0) [0|2047] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RFSRR_FO,LFSRR_FO,RSRR_FO,LRR_FO + SG_ Vpath_Data2RollCnt : 46|2@0+ (1,0) [0|3] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2YawRateV : 2|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LongVelV : 1|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,NVS_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LatVelV : 47|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2TravlDirctn : 4|2@0+ (1,0) [0|3] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LongVel : 15|12@0- (0.0625,0) [-128|127.9375] "m/s" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,NVS_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2YawRate : 19|12@0- (0.0625,0) [-128|127.9375] "deg/s" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LatVel : 39|8@0- (0.05,0) [-6.4|6.35] "m/s" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + +BO_ 161 F_Master_Time_Sync: 7 EOCM_F_FO + SG_ FTimeSyncMstrChksm : 35|12@0+ (1,0) [0|4095] "" AMM_FO,CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ FTimeSyncMstrClock : 7|32@0+ (1,0) [0|4294967295] "ms" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ SensorModeCmdLRR : 39|3@0+ (1,0) [0|7] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ SensorModeCmdSRR : 50|3@0+ (1,0) [0|7] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ SensorModeCmdFCamera : 53|3@0+ (1,0) [0|7] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ FTimeSyncMstrClockV : 36|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,LRR_FO,RFSRR_FO,LFSRR_FO + +BO_ 774 F_Vehicle_Path_Estimate: 8 EOCM_F_FO + SG_ Vpath_RollingCount : 7|2@0+ (1,0) [0|3] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_TrnCtrLngOfstV : 1|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,LRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + SG_ Vpath_Checksum : 50|11@0+ (1,0) [0|2047] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_TrnCtrLngOfst : 15|8@0- (0.1,0) [-12.8|12.7] "m" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,LRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + SG_ Vpath_TrnCtrLatOfst : 21|14@0- (1,0) [-8192|8191] "m" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,LRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + SG_ Vpath_Curvature : 39|16@0- (1E-005,0) [-0.32768|0.32767] "1/m" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_CurvatureV : 0|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,LRR_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + +BO_ 848 F_Vision_Environment: 8 VIS_FO + SG_ FwdVsnEnvIllum : 37|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnRtV : 1|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnRt : 31|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnChngStatus : 39|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseRollingCount : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseSystemOK : 4|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSnsLLnPosValid : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSenseDistToLLnEdge : 14|7@0+ (0.05,0) [0|6.35] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsRLnPosValid : 0|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsDistToRLnEdge : 22|7@0+ (0.05,0) [0|6.35] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseTimeStampV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseTimeStamp : 34|11@0+ (1,0) [0|2047] "ms" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseSystemOKV : 3|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 849 F_Vision_Environment_2: 8 VIS_FO + SG_ LnSnsLatVRelToRgtMrkg : 23|8@0- (0.02,0) [-2.56|2.54] "m/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ LnSnsRtLnMrkgTypChgDst : 61|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntRtV : 63|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnMrkgWdthRt : 62|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsRtAnchrLn : 57|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtAnchrLn : 56|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrRghtV : 0|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrRght : 47|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntRt : 31|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/rad/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstID : 2|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLatVRelToLftMrkg : 15|8@0- (0.02,0) [-2.56|2.54] "m/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 1184 R_SRR_Object_Header: 8 RSRR_FO + SG_ RSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ RSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ RSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ RSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1185 R_SRR_Object_Track1: 8 RSRR_FO + SG_ RSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1186 R_SRR_Object_Track2: 8 RSRR_FO + SG_ RSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1187 R_SRR_Object_Track3: 8 RSRR_FO + SG_ RSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1188 R_SRR_Object_Track4: 8 RSRR_FO + SG_ RSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1189 R_SRR_Object_Track5: 8 RSRR_FO + SG_ RSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1190 R_SRR_Object_Track6: 8 RSRR_FO + SG_ RSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1191 R_SRR_Object_Track7: 8 RSRR_FO + SG_ RSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1192 R_SRR_Object_Track8: 8 RSRR_FO + SG_ RSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1193 R_SRR_Object_Track9: 8 RSRR_FO + SG_ RSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1194 R_SRR_Object_Track10: 8 RSRR_FO + SG_ RSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1410 RVB_TVR_Debug: 6 EOCM_F_FO + SG_ VBBrkRqActv : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ PATOSTTC : 37|12@0+ (0.025,0) [0|102.375] "s" Dummy_FO + SG_ BWTOSObjID : 27|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ BWTOSLonPstn : 23|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ VBSwInd : 10|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ VBBrkCtrlSt : 15|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ BrkPlsRqst : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBOpSt : 12|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ VBAccelOvrrd : 0|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBUnavail : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBFld : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBDisbld : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBEnbl : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBBrkPrfReq : 5|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1216 LF_SRR_Object_Header: 8 LFSRR_FO + SG_ LFSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ LFSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ LFSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ LFSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1217 LF_SRR_Object_Track1: 8 LFSRR_FO + SG_ LFSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1218 LF_SRR_Object_Track2: 8 LFSRR_FO + SG_ LFSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1219 LF_SRR_Object_Track3: 8 LFSRR_FO + SG_ LFSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1220 LF_SRR_Object_Track4: 8 LFSRR_FO + SG_ LFSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1221 LF_SRR_Object_Track5: 8 LFSRR_FO + SG_ LFSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1222 LF_SRR_Object_Track6: 8 LFSRR_FO + SG_ LFSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1223 LF_SRR_Object_Track7: 8 LFSRR_FO + SG_ LFSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1224 LF_SRR_Object_Track8: 8 LFSRR_FO + SG_ LFSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1225 LF_SRR_Object_Track9: 8 LFSRR_FO + SG_ LFSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1226 LF_SRR_Object_Track10: 8 LFSRR_FO + SG_ LFSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1232 RF_SRR_Object_Header: 8 RFSRR_FO + SG_ RFSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ RFSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ RFSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ RFSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1233 RF_SRR_Object_Track1: 8 RFSRR_FO + SG_ RFSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1234 RF_SRR_Object_Track2: 8 RFSRR_FO + SG_ RFSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1235 RF_SRR_Object_Track3: 8 RFSRR_FO + SG_ RFSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1236 RF_SRR_Object_Track4: 8 RFSRR_FO + SG_ RFSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1237 RF_SRR_Object_Track5: 8 RFSRR_FO + SG_ RFSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1238 RF_SRR_Object_Track6: 8 RFSRR_FO + SG_ RFSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1239 RF_SRR_Object_Track7: 8 RFSRR_FO + SG_ RFSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1240 RF_SRR_Object_Track8: 8 RFSRR_FO + SG_ RFSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1241 RF_SRR_Object_Track9: 8 RFSRR_FO + SG_ RFSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1242 RF_SRR_Object_Track10: 8 RFSRR_FO + SG_ RFSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1056 F_Vision_Obj_Header: 6 VIS_FO + SG_ FVsnSnsrBlckd : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ ClstInPathVehObjID : 30|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FrtVsnFld : 6|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnIniDiagSuccCmpt : 5|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnSrvAlgnInPrcs : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnUnvlbl : 7|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVISModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FVisionNumValidTrgts : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FVisionTimeStampV : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ VISBurstChecksum : 39|16@0+ (1,0) [0|65535] "" EOCM_F_FO + +BO_ 1057 F_Vision_Obj_Track_1: 8 VIS_FO + SG_ FwdVsnRngTrk1Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk1Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr1Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk1 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisBurstIDTrk1 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk1 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk1 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk1 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk1 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ ObjDirTrk1 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1058 F_Vision_Obj_Track_2: 8 VIS_FO + SG_ FwdVsnVertPosTrk2 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk2Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk2Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ ObjDirTrk2 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FwdVsnObjTypTr2Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FVisBurstIDTrk2 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk2 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk2 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk2 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk2 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1059 F_Vision_Obj_Track_3: 8 VIS_FO + SG_ FwdVsnVertPosTrk3 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk3Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk3Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr3Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk3 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk3 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk3 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk3 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk3 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk3 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1060 F_Vision_Obj_Track_4: 8 VIS_FO + SG_ FwdVsnVertPosTrk4 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisionMeasStatTrk4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk4 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FwdVsnRngTrk4Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk4Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr4Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FVisBurstIDTrk4 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk4 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ ObjDirTrk4 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionConfTrk4 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk4 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1061 F_Vision_Obj_Track_5: 8 VIS_FO + SG_ FwdVsnVertPosTrk5 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk5Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk5Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr5Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk5 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk5 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk5 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk5 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk5 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk5 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1062 F_Vision_Obj_Track_6: 8 VIS_FO + SG_ FwdVsnVertPosTrk6 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk6Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk6Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr6Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk6 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk6 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk6 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk6 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk6 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk6 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1538 LF_SRR_Trace_Data: 8 LFSRR_FO + SG_ LFSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ LFSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ LFSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 1537 R_SRR_Trace_data: 8 RSRR_FO + SG_ RSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 1089 F_Vision_Obj_Track_7: 8 VIS2_FO + SG_ FVisBurstIDTrk7 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk7 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk7 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk7 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk7 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FwdVsnRngTrk7Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnObjTypTr7Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk7Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnVertPosTrk7 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ ObjDirTrk7 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1090 F_Vision_Obj_Track_8: 8 VIS2_FO + SG_ FVisBurstIDTrk8 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk8 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk8Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnVertPosTrk8 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk8Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnObjTypTr8Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk8 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionConfTrk8 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk8 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk8 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1091 F_Vision_Obj_Track_9: 8 VIS2_FO + SG_ FwdVsnVertPosTrk9 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk9Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk9Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr9Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk9 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk9 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk9 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk9 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk9 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk9 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1092 F_Vision_Obj_Track_10: 8 VIS2_FO + SG_ FwdVsnRngTrk10Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk10Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr10Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk10 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ ObjDirTrk10 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk10 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk10 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk10 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk10 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk10 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1120 F_LRR_Obj_Header: 8 LRR_FO + SG_ FLRRRollingCount : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRModeCmdFdbk : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRNumValidTargets : 20|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ FLRRTimeStampV : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTimeStamp : 2|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ FLRRRoadTypeInfo : 5|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ FLRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRLonVelPlsblityFlt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRYawRtPlsblityFlt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTunlDtctd : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1121 F_LRR_Obj_Track_1: 8 LRR_FO + SG_ FLRRTrk1BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk1Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk1RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk1RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk1DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk1Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk1Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk1MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk1ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk1Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1122 F_LRR_Obj_Track_2: 8 LRR_FO + SG_ FLRRTrk2BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk2Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk2RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk2RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk2DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk2Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk2Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk2MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk2ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk2Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1123 F_LRR_Obj_Track_3: 8 LRR_FO + SG_ FLRRTrk3BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk3Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk3RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk3RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk3DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk3Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk3Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk3MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk3ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk3Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1124 F_LRR_Obj_Track_4: 8 LRR_FO + SG_ FLRRTrk4BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk4Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk4RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk4RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk4DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk4Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk4Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk4MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk4ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk4Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1125 F_LRR_Obj_Track_5: 8 LRR_FO + SG_ FLRRTrk5BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk5Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk5RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk5RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk5DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk5Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk5Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk5MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk5ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk5Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1126 F_LRR_Obj_Track_6: 8 LRR_FO + SG_ FLRRTrk6BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk6Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk6RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk6Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk6RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk6DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk6Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk6Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk6MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk6ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1127 F_LRR_Obj_Track_7: 8 LRR_FO + SG_ FLRRTrk7Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk7BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk7Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk7RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk7RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk7DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk7Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk7Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk7MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk7ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1128 F_LRR_Obj_Track_8: 8 LRR_FO + SG_ FLRRTrk8Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk8BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk8Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk8RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk8RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk8DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk8Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk8Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk8MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk8ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1129 F_LRR_Obj_Track_9: 8 LRR_FO + SG_ FLRRTrk9Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk9BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk9Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk9RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk9RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk9DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk9Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk9Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk9MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk9ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1130 F_LRR_Obj_Track_10: 8 LRR_FO + SG_ FLRRTrk10Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk10BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk10Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk10RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk10RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk10DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk10Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk10Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk10MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk10ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1131 F_LRR_Obj_Track_11: 8 LRR_FO + SG_ FLRRTrk11Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk11BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk11Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk11RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk11RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk11DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk11Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk11Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk11MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk11ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1132 F_LRR_Obj_Track_12: 8 LRR_FO + SG_ FLRRTrk12Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk12BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk12Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk12RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk12RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk12DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk12Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk12Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk12MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk12ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1133 F_LRR_Obj_Track_13: 8 LRR_FO + SG_ FLRRTrk13Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk13RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk13RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk13DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk13Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk13Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk13MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1134 F_LRR_Obj_Track_14: 8 LRR_FO + SG_ FLRRTrk14Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk14BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk14Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk14RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk14RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk14DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk14Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk14Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk14MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk14ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1135 F_LRR_Obj_Track_15: 8 LRR_FO + SG_ FLRRTrk15Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk15MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk15Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk15ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk15BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk15Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk15RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk15RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk15DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk15Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + +BO_ 1136 F_LRR_Obj_Track_16: 8 LRR_FO + SG_ FLRRTrk16Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk16BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk16Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk16RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk16RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk16DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk16Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk16Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk16MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk16ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1137 F_LRR_Obj_Track_17: 8 LRR_FO + SG_ FLRRTrk17Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk17BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk17Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk17RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk17RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk17DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk17Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk17Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk17MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk17ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1138 F_LRR_Obj_Track_18: 8 LRR_FO + SG_ FLRRTrk18Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk18BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk18Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk18RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk18RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk18DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk18Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk18Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk18MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk18ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1139 F_LRR_Obj_Track_19: 8 LRR_FO + SG_ FLRRTrk19Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk19BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk19Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk19RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk19RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk19DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk19Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk19Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk19MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk19ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1140 F_LRR_Obj_Track_20: 8 LRR_FO + SG_ FLRRTrk20Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk20BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk20Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk20RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk20RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk20DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk20Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk20Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk20MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk20ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1141 Long_Range_Radar_add_Info_1: 8 LRR_FO + SG_ FLRRAddInfo1BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk1 : 15|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk1 : 9|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk2 : 23|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk2 : 17|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk3 : 31|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk3 : 25|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk4 : 39|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk4 : 33|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk5 : 47|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk5 : 41|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk6 : 55|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk6 : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1321 F_Fwd_Fus_Obj_TrackB_9: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn9 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB9RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB9Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB9MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB9DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB9RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB9RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB9Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB9ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB9ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB9NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB9LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB9LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1320 F_Fwd_Fus_Obj_TrackB_8: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn8 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB8RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB8Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB8MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB8DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB8RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB8RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB8Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB8ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB8ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB8NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB8LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB8LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1319 F_Fwd_Fus_Obj_TrackB_7: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn7 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB7RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB7Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB7MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB7DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB7RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB7RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB7Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB7ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB7ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB7NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB7LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB7LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1318 F_Fwd_Fus_Obj_TrackB_6: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn6 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB6RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB6Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB6MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB6DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB6RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB6RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB6Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB6ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB6ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB6NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB6LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB6LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1317 F_Fwd_Fus_Obj_TrackB_5: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn5 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB5RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB5Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB5MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB5DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB5RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB5RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB5Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB5ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB5ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB5NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB5LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB5LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1316 F_Fwd_Fus_Obj_TrackB_4: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn4 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB4RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB4Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB4MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB4DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB4RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB4RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB4Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB4ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB4ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB4NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB4LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB4LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1315 F_Fwd_Fus_Obj_TrackB_3: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn3 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB3RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB3Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB3MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB3DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB3RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB3RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB3Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB3ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB3ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB3NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB3LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB3LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1314 F_Fwd_Fus_Obj_TrackB_2: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn2 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB2RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB2Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB2MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB2DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB2RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB2RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB2Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB2ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB2ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB2NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB2LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB2LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1327 F_Fwd_Fus_Obj_TrackB_15: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn15 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB15RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB15Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB15MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB15DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB15RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB15RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB15Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB15ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB15ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB15ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB15ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTkB15ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB15ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB15NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB15LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB15LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1326 F_Fwd_Fus_Obj_TrackB_14: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn14 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB14RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB14Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB14MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB14DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB14RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB14RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB14Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB14ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB14ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB14NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB14LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB14LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1325 F_Fwd_Fus_Obj_TrackB_13: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn13 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB13RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB13Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB13MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB13DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB13RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB13RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB13Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB13ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB13ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB13NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB13LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB13LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1324 F_Fwd_Fus_Obj_TrackB_12: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn12 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB12RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB12Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB12MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB12DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB12RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB12RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB12Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB12ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB12ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB12NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB12LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB12LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1323 F_Fwd_Fus_Obj_TrackB_11: 7 EOCM_F_FO + SG_ FwdFusTrkB11DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB11RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB11RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB11Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB11ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB11ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB11NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB11LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB11LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkBAnlgRlLn11 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB11RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB11Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB11MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + +BO_ 1322 F_Fwd_Fus_Obj_TrackB_10: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn10 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB10RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB10Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB10MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB10DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB10RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB10RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB10Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB10ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB10ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB10NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB10LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB10LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1313 F_Fwd_Fus_Obj_TrackB_1: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn1 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB1RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB1Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB1MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB1DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB1RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB1RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB1Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB1ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB1ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB1NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB1LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB1LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1305 F_Fwd_Fus_Obj_TrackA_9: 8 EOCM_F_FO + SG_ FwdFusTrkA9RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA9ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA9MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA9LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA9RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA9Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA9LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA9RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA9MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA9ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1304 F_Fwd_Fus_Obj_TrackA_8: 8 EOCM_F_FO + SG_ FwdFusTrkA8RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA8ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA8MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA8LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA8RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA8Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA8LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA8RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA8MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA8ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1303 F_Fwd_Fus_Obj_TrackA_7: 8 EOCM_F_FO + SG_ FwdFusTrkA7RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA7ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA7MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA7LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA7RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA7Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA7LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA7RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA7MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA7ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1302 F_Fwd_Fus_Obj_TrackA_6: 8 EOCM_F_FO + SG_ FwdFusTrkA6RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA6ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA6MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA6LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA6RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA6Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA6LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA6RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA6MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA6ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1301 F_Fwd_Fus_Obj_TrackA_5: 8 EOCM_F_FO + SG_ FwdFusTrkA5RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA5ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA5MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA5LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA5RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA5Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA5LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA5RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA5MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA5ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1300 F_Fwd_Fus_Obj_TrackA_4: 8 EOCM_F_FO + SG_ FwdFusTrkA4RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA4ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA4MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA4LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA4RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA4Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA4LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA4RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA4MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA4ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1299 F_Fwd_Fus_Obj_TrackA_3: 8 EOCM_F_FO + SG_ FwdFusTrkA3RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA3ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA3MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA3LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA3RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA3Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA3LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA3RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA3MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA3ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1298 F_Fwd_Fus_Obj_TrackA_2: 8 EOCM_F_FO + SG_ FwdFusTrkA2RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA2ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA2MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA2LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA2RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA2Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA2LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA2RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA2MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA2ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1311 F_Fwd_Fus_Obj_TrackA_15: 8 EOCM_F_FO + SG_ FwdFusTrkA15RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA15ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA15MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA15LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA15RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA15Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA15LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA15RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA15MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA15ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1310 F_Fwd_Fus_Obj_TrackA_14: 8 EOCM_F_FO + SG_ FwdFusTrkA14RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA14ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA14MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA14LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA14RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA14Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA14LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA14RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA14MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA14ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1309 F_Fwd_Fus_Obj_TrackA_13: 8 EOCM_F_FO + SG_ FwdFusTrkA13RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA13ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA13MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA13LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA13RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA13Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA13LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA13RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA13MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA13ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1308 F_Fwd_Fus_Obj_TrackA_12: 8 EOCM_F_FO + SG_ FwdFusTrkA12RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA12ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA12MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA12LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA12RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA12Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA12LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA12RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA12MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA12ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1307 F_Fwd_Fus_Obj_TrackA_11: 8 EOCM_F_FO + SG_ FwdFusTrkA11ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA11MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA11LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA11RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA11Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA11LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA11RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA11MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA11ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkA11RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + +BO_ 1306 F_Fwd_Fus_Obj_TrackA_10: 8 EOCM_F_FO + SG_ FwdFusTrkA10RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA10ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA10MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA10LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA10RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA10Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA10LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA10RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA10MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA10ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1297 F_Fwd_Fus_Obj_TrackA_1: 8 EOCM_F_FO + SG_ FwdFusTrkA1RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA1ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA1MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA1LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA1RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA1Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA1LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA1RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA1MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA1ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1296 F_Fwd_Fus_Obj_Header: 7 EOCM_F_FO + SG_ F_FusHeadRollingCount : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ F_FusHeadFuncState : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ F_FusHedNmValTargts : 3|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ F_FusHead_LrrOK : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_LFSRROK : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_VIsOK : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_MapDataOK : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHeadTimStmpV : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHeadTimStmp : 10|11@0+ (1,0) [0|2047] "ms" Dummy_FO + SG_ F_FusHead_LCSRROK : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_RCSRROK : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_RFSRROK : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHed_ObjClstrCurv : 28|13@0- (5E-005,0) [-0.2048|0.20475] "1/m" Dummy_FO + SG_ F_FusHdObjClstTanHdng : 47|8@0- (0.002,0) [-0.256|0.254] "m/m" Dummy_FO + SG_ RoadTypeInfo : 55|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 257 USDT_Req_to_All_FO_ECUs: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LRSRR_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2A_K2_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K1_FO,NVS_FO,CIPM_FO,VIS2_FO,RRSRR_FO,VIS_FO,RFSRR_FO,LRR_FO,LFSRR_FO,RSRR_FO,EOCM_F_FO + +BO_ 584 USDT_Req_to_6DOFIMU2_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" _DOFIMU2_FO + +BO_ 1348 UUDT_Resp_From_6DOFIMU1_FO: 8 _DOFIMU1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1604 USDT_Resp_From_6DOFIMU1_FO: 8 _DOFIMU1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 580 USDT_Req_to_6DOFIMU1_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" _DOFIMU1_FO + +BO_ 1349 UUDT_Resp_From_DMS_FO: 8 DMS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1605 USDT_Resp_From_DMS_FO: 8 DMS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 581 USDT_Req_to_DMS_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" DMS_FO + +BO_ 1372 UUDT_Resp_From_AMM_FO: 8 AMM_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1628 USDT_Resp_From_AMM_FO: 8 AMM_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 604 USDT_Req_to_AMM_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" AMM_FO + +BO_ 1622 USDT_Resp_From_EOCM2B_IMX6_FO: 8 EOCM2B_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1366 UUDT_Resp_From_EOCM2B_IMX6_FO: 8 EOCM2B_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 598 USDT_Req_to_EOCM2B_IMX6_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2B_IMX6_FO + +BO_ 590 USDT_Req_to_Free_4E_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Vector__XXX + +BO_ 1338 VPDR_Debug: 8 EOCM_F_FO + SG_ FrtRWARateDiagFA : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FrtRWABiasDiagFA : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ HWAFrtVal : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ HWADotValFrt : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxRangeFA : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxRateFA : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxBiasFA : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAxCompFA : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxVal : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxVal : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FrtRWACorrFA : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FrtRWARangeDiagFA : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyBiasFA : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAyCompFA : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyVal : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyVal : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAxCorrFA : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxRangeFA : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxRateFA : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxBiasFA : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzVal : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzVal : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAyCorrDiagFA : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyRangeFA : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyRateFA : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyBiasFA : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyRangeFA : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyRateFA : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehWzCorrDiagFA : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzRangeFA : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzRateFA : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzBiasFA : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzRangeFA : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzRateFA : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzBiasFA : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehWzCompFA : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxLFCorrDiagFA : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxRFCorrDiagFA : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxLRCorrDiagFA : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxRRCorrDiagFA : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlLFVal : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlRFVal : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlLRVal : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlRRVal : 0|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1328 Diag_Debug1: 8 EOCM_F_FO + SG_ AlrtWrnIndReqFP : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AlrtWrnIndReqFA : 0|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILRSRRSnsr_FP : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILRSRRSnsr_FA : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILRSRRFrehns_FA : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathEstCrvCSFP : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathEstCrvCSFA : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathWzEstCSFP : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathWzEstCSFA : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVyEstCSFP : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVyEstCSFA : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVxEstCSFP : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVxEstCSFA : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCCSFP : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCCSFA : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyCSFP : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyCSFA : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThLxVxAxCSFP : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThLxVxAxCSFA : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CurSetValDiagFP : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CurSetValDiagFA : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CrsAltDvrSlTpDiagFP : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CrsAltDvrSlTpDiagFA : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCAStatDiagFP : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCAStatDiagFA : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlStFP : 62|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlStFA : 61|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBOpStFP : 60|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBOpStFA : 59|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlAccFP : 58|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlAccFA : 57|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBAxlTrqRqFP : 56|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBAxlTrqRqFA : 55|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRUPATTCFP : 54|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRUPATTCFA : 53|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtObjIDFP : 52|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtObjIDFA : 51|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtTTCFP : 50|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtTTCFA : 49|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLxFP : 48|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLxFA : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLyFP : 46|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLyFA : 45|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFFuncStFP : 44|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFFuncStFA : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFObjIDFP : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFObjIDFA : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLatPstnVelRatFP : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLatPstnVelRatFA : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelFP : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelFA : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatVelDiagFP : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatVelDiagFA : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatPstnDiagFP : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatPstnDiagFA : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFNrRltvLonPstnFP : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFNrRltvLonPstnFA : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelRatFP : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelRatFA : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFConfDiagFP : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFConfDiagFA : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLnDiagFP : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLnDiagFA : 25|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1335 Diag_Debug3: 8 EOCM_F_FO + SG_ BrkSysCmdAxDiagFPQ : 63|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ BrkSysCmdAxDiagFAQ : 62|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFPQ : 61|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFAQ : 60|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFPQ : 59|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFAQ : 58|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFPQ : 57|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFAQ : 56|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTmpMemFPQ : 55|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTmpMemFAQ : 54|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFPQ : 53|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFAQ : 52|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFPQ : 51|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFAQ : 50|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFPQ : 49|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFAQ : 48|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFPQ : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFAQ : 46|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFPQ : 45|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFAQ : 44|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFPQ : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFAQ : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFPQ : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFAQ : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFPQ : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFAQ : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFPQ : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFAQ : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFPQ : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFAQ : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFPQ : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFAQ : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFPQ : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFAQ : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFPQ : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFAQ : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFPQ : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFAQ : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFPQ : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFAQ : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFPQ : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFAQ : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFPQ : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFAQ : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFOvrlpRtlChk_FAQ : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFOvrlpRtlChk_FAQ : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRROvrlpRtlChk_FAQ : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISOvrlpRtlChk_FAQ : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISAlign_FAQ : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FAQ : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FPQ : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISFrshns_FAQ : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRAlign_FAQ : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRFrshns_FAQ : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FAQ : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FPQ : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRAlign_FAQ : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRFrehns_FAQ : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FAQ : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FPQ : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FPQ : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FAQ : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRFrshns_FAQ : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRAlign_FAQ : 0|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1331 Diag_Debug2: 8 EOCM_F_FO + SG_ TCPHiThrtTmpMemFP : 63|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTmpMemFA : 62|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFP : 61|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFA : 60|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFP : 59|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFP : 58|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFA : 57|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFP : 56|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFA : 55|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFP : 54|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFA : 53|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFP : 52|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFA : 51|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFP : 50|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFA : 49|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFA : 48|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ BrkSysCmdAxDiagFP : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ BrkSysCmdAxDiagFA : 46|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFP : 45|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFA : 44|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFP : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFA : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFA : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFP : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFP : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFA : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFP : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFA : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFP : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFA : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFP : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFA : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFP : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFA : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFP : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFA : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFP : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFA : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFP : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFA : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFP : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFA : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFP : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFA : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISOvrlpRtlChk_FA : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRROvrlpRtlChk_FA : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFOvrlpRtlChk_FA : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFOvrlpRtlChk_FA : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISAlign_FA : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISFrshns_FA : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FP : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FA : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRAlign_FA : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRFrshns_FA : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FP : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FA : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRAlign_FA : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRFrehns_FA : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FP : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FA : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRAlign_FA : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRFrshns_FA : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FP : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FA : 0|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1787 AL_Test_Tool_Rsp_RFSRR: 8 RFSRR_FO + SG_ RFSRREngRspDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Dummy_FO + +BO_ 1788 AL_Test_Tool_Rsp_LFSRR: 8 LFSRR_FO + SG_ LFSRREngRspDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Dummy_FO + +BO_ 1790 AL_Test_Tool_Req_RFSRR: 8 Dummy_FO + SG_ RFSRREngCmdDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RFSRR_FO + +BO_ 1791 AL_Test_Tool_Req_LFSRR: 8 Dummy_FO + SG_ LFSRREngCmdDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LFSRR_FO + +BO_ 1786 AL_Test_Tool_Rsp_RSRR: 8 RSRR_FO + SG_ RSRREngRspDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Dummy_FO + +BO_ 1789 AL_Test_Tool_Req_RSRR: 8 Dummy_FO + SG_ RSRREngCmdDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RSRR_FO + +BO_ 1149 F_LRR_Azmth_Rate_Info_4: 8 LRR_FO + SG_ FLRRTrk20AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk19AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk18AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk17AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk16AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf4BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1148 F_LRR_Azmth_Rate_Info_3: 8 LRR_FO + SG_ FLRRTrk15AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk14AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk13AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk12AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk11AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf3BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1147 F_LRR_Azmth_Rate_Info_2: 8 LRR_FO + SG_ FLRRTrk9AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk8AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk7AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk6AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk10AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf2BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1146 F_LRR_Azmth_Rate_Info_1: 8 LRR_FO + SG_ FLRRTrk5AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk4AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk3AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk2AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk1AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf1BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1143 Long_Range_Radar_add_Info_3: 8 LRR_FO + SG_ FLRRAddInfo3BurstID : 57|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13ObstType : 60|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk20ObstTypeConf : 52|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk20ObstType : 55|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk19ObstTypeConf : 44|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk19ObstType : 47|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk18ObstTypeConf : 36|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk18ObstType : 39|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk17ObstTypeConf : 28|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk17ObstType : 31|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk16ObstTypeConf : 20|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk16ObstType : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk15ObstTypeConf : 12|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk15ObstType : 15|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk14ObstTypeConf : 4|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk14ObstType : 7|3@0+ (1,0) [0|7] "" EOCM_F_FO + +BO_ 1142 Long_Range_Radar_add_Info_2: 8 LRR_FO + SG_ FLRRAddInfo2BurstID : 62|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13ObstTypeConf : 60|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk12ObstTypeConf : 52|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk12ObstType : 55|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk11ObstTypeConf : 44|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk11ObstType : 47|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk10ObstTypeConf : 36|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk10ObstType : 39|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk9ObstTypeConf : 28|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk9ObstType : 31|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk8ObstTypeConf : 20|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk8ObstType : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk7ObstTypeConf : 12|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk7ObstType : 15|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk1ObstTypeConf : 4|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk1ObstType : 7|3@0+ (1,0) [0|7] "" EOCM_F_FO + +BO_ 851 F_Vision_Environment_4: 8 VIS_FO + SG_ LnMrkg3LnPrvwDst : 45|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTtlNmLnMrkgDetRt : 4|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsRtLinCrsTm : 25|5@0+ (0.1,0) [0|3.1] "s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsNumPrlLnsDetRt : 33|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsNumPrlLnsDetLt : 36|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntLftV : 31|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtLinCrsTm : 30|5@0+ (0.1,0) [0|3.1] "s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnPrvwDst : 50|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMrkgTypChgDst : 61|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMrkgTypChgDst : 40|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMrkgWdth : 62|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMarkrElvtd : 51|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4AnchrLnLin : 57|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMrkgWdth : 41|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMarkrElvtd : 46|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3AnchrLnLin : 52|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstID2 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntLft : 15|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/rad/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 597 USDT_Req_to_VIS2_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" CIPM_FO,VIS2_FO + +BO_ 1204 RR_SRR_Object_Track4: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1203 RR_SRR_Object_Track3: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1202 RR_SRR_Object_Track2: 8 RRSRR_FO + SG_ RRSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + +BO_ 1201 RR_SRR_Object_Track1: 8 RRSRR_FO + SG_ RRSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + +BO_ 1200 RR_SRR_Object_Header: 8 RRSRR_FO + SG_ RRSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "" EOCM_F_FO + SG_ RRSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ RRSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + +BO_ 850 F_Vision_Environment_3: 8 VIS_FO + SG_ LnSnsTtlNmLnMrkgDetLt : 58|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtLnMrkgWdth : 63|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtLnMrkgTypChgDst : 62|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnLftV : 23|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnLft : 31|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrLftV : 15|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrLft : 39|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrTypRght : 50|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrTypLft : 53|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrElvtdRght : 54|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrElvtdLft : 55|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstID1 : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnQltyCnfdncLvlRght : 22|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnQltyCnfdncLvlLft : 14|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnPrvwDstncRght : 2|3@0+ (10,0) [0|70] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnPrvwDstncLft : 5|3@0+ (10,0) [0|70] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 1414 RVB_TVR_Debug2_FO: 7 EOCM_F_FO + SG_ VBBrkCntlAccel : 45|12@0- (0.01,0) [-20.48|20.47] "m/s^2" Dummy_FO + SG_ VBTOSObjID : 35|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ VBTOSTTC : 31|12@0+ (0.025,0) [0|102.375] "s" Dummy_FO + SG_ VBTOSLatPstn : 11|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ VBTOSLonPstn : 7|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + diff --git a/opendbc/cadillac_ct6_powertrain.dbc b/opendbc/cadillac_ct6_powertrain.dbc new file mode 100644 index 00000000000000..f139b1dbd4a734 --- /dev/null +++ b/opendbc/cadillac_ct6_powertrain.dbc @@ -0,0 +1,244 @@ +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_: K16_BECM K73_TCIC K9_BCM K43_PSCM K17_EBCM K20_ECM K114B_HPCM NEO K124_ASCM +VAL_TABLE_ TurnSignals 2 "Right Turn" 1 "Left Turn" 0 "None" ; +VAL_TABLE_ ACCLeadCar 1 "Present" 0 "Not Present" ; +VAL_TABLE_ ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_TABLE_ DistanceButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKAButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_TABLE_ PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; +VAL_TABLE_ DoorStatus 1 "Opened" 0 "Closed" ; +VAL_TABLE_ SeatBeltStatus 1 "Latched" 0 "Unlatched" ; +VAL_TABLE_ LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; +VAL_TABLE_ GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_TABLE_ GasRegenCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HandsOffSWDetectionStatus 1 "Hands On" 0 "Hands Off" ; +VAL_TABLE_ HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; + + +BO_ 717 ASCM_2CD: 5 K124_ASCM + +BO_ 869 ASCM_365: 4 K124_ASCM + +BO_ 1034 ASCM_40A: 7 K124_ASCM + +BO_ 1296 ASCM_510: 4 K124_ASCM + +BO_ 1930 ASCM_78A: 7 K124_ASCM + +BO_ 190 ECMAcceleratorPos: 6 K20_ECM + SG_ BrakePedalPos : 15|8@0+ (1,0) [0|0] "sticky" NEO + SG_ GasPedalAndAcc : 23|8@0+ (1,0) [0|0] "" NEO + +BO_ 201 ECMEngineStatus: 8 K20_ECM + SG_ EngineTPS : 39|8@0+ (0.392156863,0) [0|100.000000065] "%" NEO + SG_ EngineRPM : 15|16@0+ (0.25,0) [0|0] "RPM" NEO + +BO_ 209 EBCMBrakePedalTorque: 7 K17_EBCM + SG_ BrakePedalTorque : 3|12@0+ (1,0) [0|0] "" NEO + +BO_ 241 EBCMBrakePedalPosition: 6 K17_EBCM + SG_ BrakePedalPosition : 15|8@0+ (1,0) [0|255] "" NEO + +BO_ 298 BCMDoorBeltStatus: 8 K9_BCM + SG_ RearLeftDoor : 8|1@0+ (1,0) [0|0] "" NEO + SG_ FrontLeftDoor : 9|1@0+ (1,0) [0|0] "" NEO + SG_ FrontRightDoor : 10|1@0+ (1,0) [0|0] "" NEO + SG_ RearRightDoor : 23|1@0+ (1,0) [0|0] "" NEO + SG_ LeftSeatBelt : 12|1@0+ (1,0) [0|0] "" NEO + SG_ RightSeatBelt : 53|1@0+ (1,0) [0|0] "" NEO + +BO_ 309 ECMPRDNL: 8 K20_ECM + SG_ PRNDL : 2|3@0+ (1,0) [0|0] "" NEO + +BO_ 320 BCMTurnSignals: 3 K9_BCM + SG_ TurnSignals : 19|2@0+ (1,0) [0|0] "" NEO + +BO_ 336 ASCMLKASStatus: 1 NEO + SG_ Available : 7|1@0+ (1,0) [0|0] "" NEO + +BO_ 338 ASCMLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASMode : 36|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 340 ASCMBLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASMode : 36|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 381 MSG_17D: 8 K20_ECM + SG_ MSG17D_AccPower : 35|12@0- (1,0) [0|0] "" NEO + +BO_ 356 PSCMStatus: 8 K43_PSCM + SG_ LKATorqueDeliveredStatus : 7|3@0+ (1,0) [0|7] "" NEO + SG_ LKADriverAppldTrq : 2|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO + SG_ LKATBDTorque : 21|14@0- (-0.005,0) [-10.24|10.23] "Nm" NEO + SG_ RollingCounter : 39|2@0+ (1,0) [0|0] "" NEO + SG_ LKATotalTorqueDelivered : 37|14@0- (0.01,0) [-10.24|10.23] "Nm" NEO + +BO_ 417 AcceleratorPedal: 7 XXX + SG_ AcceleratorPedal : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 451 GasAndAcc: 8 XXX + SG_ GasPedalAndAcc2 : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 452 AcceleratorPedal2: 8 XXX + SG_ AcceleratorPedal2 : 47|8@0+ (1,0) [0|0] "" NEO + +BO_ 481 ASCMSteeringButton: 7 K124_ASCM + SG_ DistanceButton : 22|1@0+ (1,0) [0|0] "" NEO + SG_ LKAButton : 23|1@0+ (1,0) [0|0] "" NEO + SG_ ACCButtons : 46|3@0+ (1,0) [0|0] "" NEO + +BO_ 485 PSCMSteeringAngle: 8 K43_PSCM + SG_ SteeringWheelAngle : 15|16@0- (0.0625,0) [-540|540] "deg" NEO + SG_ SteeringWheelRate : 27|12@0- (0.5,0) [-100|100] "deg/s" NEO + +BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM + SG_ YawRate : 51|12@0- (0.0625,0) [-2047|2047] "grad/s" NEO + SG_ LateralAcceleration : 3|12@0- (0.0161,0) [-2047|2047] "m/s2" NEO + SG_ BrakePedalPressed : 6|1@0+ (1,0) [0|0] "" NEO + +BO_ 711 BECMBatteryVoltageCurrent: 6 K17_EBCM + SG_ HVBatteryVoltage : 31|12@0+ (0.125,0) [0|511.875] "V" NEO + SG_ HVBatteryCurrent : 12|13@0- (0.15,0) [-614.4|614.25] "A" NEO + +BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM + SG_ GasRegenAlwaysOne : 9|1@0+ (1,1) [1|1] "" NEO + SG_ GasRegenAlwaysThree : 15|2@0+ (1,1) [1|1] "" NEO + SG_ GasRegenChecksum : 47|24@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActiveInv : 32|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenFullStopActive : 13|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActive : 0|1@0+ (1,0) [0|0] "" NEO + SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" NEO + SG_ RollingCounter2 : 36|4@0+ (1,0) [0|0] "" NEO + SG_ GasRegenAlwaysOne2 : 23|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenCmd : 22|15@0+ (1,0) [0|0] "" NEO + +BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC + SG_ GPSLongitude : 39|32@0+ (1,0) [0|0] "milliarcsecond" NEO + SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO + +BO_ 840 EBCMWheelSpdFront: 4 K17_EBCM + SG_ FLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO + SG_ FRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO + +BO_ 842 EBCMWheelSpdRear: 4 K17_EBCM + SG_ RLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO + SG_ RRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO + +BO_ 880 ASCMActiveCruiseControlStatus: 6 K124_ASCM + SG_ ACCLeadCar : 44|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne2 : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCSpeedSetpoint : 19|12@0+ (1,0) [0|0] "km/h" NEO + SG_ ACCGapLevel : 21|2@0+ (1,0) [0|0] "" NEO + SG_ ACCResumeButton : 1|1@0+ (1,0) [0|0] "" NEO + SG_ ACCCmdActive : 23|1@0+ (1,0) [0|0] "" NEO + +BO_ 1001 ECMVehicleSpeed: 8 K20_ECM + SG_ VehicleSpeed : 7|16@0+ (0.01,0) [0|0] "mph" NEO + +BO_ 1033 ASCMKeepAlive: 7 NEO + SG_ ASCMKeepAliveAllZero : 7|56@0+ (1,0) [0|0] "" NEO + +BO_ 1217 ECMEngineCoolantTemp: 8 K20_ECM + SG_ EngineCoolantTemp : 23|8@0+ (1,-40) [0|0] "°C" NEO + +BO_ 1249 VIN_Part2: 8 K20_ECM + SG_ VINPart2 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1300 VIN_Part1: 8 K20_ECM + SG_ VINPart1 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1912 PSCM_778: 8 K43_PSCM + +BO_TX_BU_ 338 : K124_ASCM,NEO; +BO_TX_BU_ 880 : NEO,K124_ASCM; +BO_TX_BU_ 1033 : K124_ASCM,NEO; +BO_TX_BU_ 715 : NEO,K124_ASCM; + + +CM_ BU_ K16_BECM "Battery Energy Control Module"; +CM_ BU_ K73_TCIC "Telematics Communication Control Module"; +CM_ BU_ K9_BCM "Body Control Module"; +CM_ BU_ K43_PSCM "Power Steering Control Module"; +CM_ BU_ K17_EBCM "Electronic Brake Control Module"; +CM_ BU_ K20_ECM "Engine Control Module"; +CM_ BU_ K114B_HPCM "Hybrid Powertrain Control Module"; +CM_ BU_ NEO "Comma NEO"; +CM_ BU_ K124_ASCM "Active Safety Control Module"; +CM_ SG_ 381 MSG17D_AccPower "Need to investigate"; +CM_ SG_ 190 GasPedalAndAcc "ACC baseline is 62"; +CM_ SG_ 451 GasPedalAndAcc2 "ACC baseline is 62"; +CM_ SG_ 715 RollingCounter2 "Values cycle between 0, 7, 10, 13"; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; +BA_ "UseGMParameterIDs" 0; +VAL_ 481 DistanceButton 1 "Active" 0 "Inactive" ; +VAL_ 481 LKAButton 1 "Active" 0 "Inactive" ; +VAL_ 481 ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_ 309 PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; +VAL_ 338 LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 338 LKASMode 2 "supercruise" 1 "lkas" 0 "Inactive" ; +VAL_ 880 ACCLeadCar 1 "Present" 0 "Not Present" ; +VAL_ 880 ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; +VAL_ 880 ACCResumeButton 1 "Pressed" 0 "Depressed" ; +VAL_ 880 ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 356 LKATorqueDeliveredStatus 7 "Override Fault" 6 "LKAS Fault but Responsive" 5 "TBD but Responsive" 4 "TBD but Responsive" 3 "Fault" 1 "Active" 0 "Inactive" ; +VAL_ 489 BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_ 715 GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ; + diff --git a/opendbc/chrysler_pacifica_2017_hybrid.dbc b/opendbc/chrysler_pacifica_2017_hybrid.dbc new file mode 100644 index 00000000000000..a56ccfaaa38ee1 --- /dev/null +++ b/opendbc/chrysler_pacifica_2017_hybrid.dbc @@ -0,0 +1,426 @@ +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_: XXX + + +BO_ 258 STEERING: 8 XXX + SG_ INCREMENTING_STEERING : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_STEERING : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_STEERING : 48|3@1+ (1,0) [0|15] "" XXX + SG_ STEERING_RATE : 20|13@0+ (0.3187251,-1305.498) [0|8191] "deg/s" XXX + SG_ STEER_ANGLE : 4|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX + +BO_ 514 SPEED_1: 4 XXX + SG_ SPEED_LEFT : 7|12@0+ (0.071028,0) [0|65535] "m/s" XXX + SG_ SPEED_RIGHT : 23|12@0+ (0.071028,0) [0|1023] "m/s" XXX + +BO_ 653 BRAKE_MODULE: 2 XXX + SG_ BRAKE_PRESSURE : 15|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|4] "" XXX + +BO_ 820 DOORS: 8 XXX + SG_ DOOR_OPEN_FR : 18|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 20|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_TRUNK : 22|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 17|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_LIGHT_LEFT : 31|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_LIGHT_RIGHT : 30|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAM_DISPLAY : 58|1@1+ (1,0) [0|1] "" XXX + +BO_ 746 GEAR: 5 XXX + SG_ PRNDL : 2|3@0+ (1,0) [0|7] "" XXX + SG_ GEAR_CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR_INCREMENTING : 31|4@0+ (1,0) [0|15] "" XXX + +BO_ 284 BRAKE_1: 8 XXX + SG_ SPEED_RELATED_1 : 37|14@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_RELATED_1_2 : 18|11@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_RELATED_1_1 : 3|12@0+ (1,0) [0|255] "" XXX + SG_ INCREMENTING_BRAKE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_BRAKE : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 320 BRAKE_2: 8 XXX + SG_ SPEED_RELATED_2 : 47|8@0+ (1,0) [0|63] "" XXX + SG_ INCREMENTING_140 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_140 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PRESSED_2 : 2|3@0+ (1,0) [0|7] "" XXX + SG_ BRAKE_PRESSED_ACC : 6|1@0+ (1,0) [0|3] "" XXX + +BO_ 736 TRIP: 8 XXX + SG_ DISTANCE_COUNTER : 7|16@0+ (1,0) [0|65535] "Meters" XXX + SG_ DISTANCE_COUNTER_2 : 23|16@0+ (1,0) [0|65535] "Meters" XXX + +BO_ 344 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FL : 3|12@0+ (0.0189408,0) [0|65535] "m/s" XXX + SG_ WHEEL_SPEED_RR : 51|12@0+ (0.0189408,0) [0|255] "m/s" XXX + SG_ WHEEL_SPEED_RL : 35|12@0+ (0.0189408,0) [0|3] "m/s" XXX + SG_ WHEEL_SPEED_FR : 19|12@0+ (0.0189408,0) [0|255] "m/s" XXX + +BO_ 792 STEERING_LEVERS: 8 XXX + SG_ HIGH_BEAM_PUSHED_IN : 2|1@0+ (1,0) [0|3] "" XXX + SG_ TURN_SIGNALS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ HIGH_BEAM_FLASH : 3|1@0+ (1,0) [0|3] "" XXX + +BO_ 264 ACCEL_PEDAL_MSG: 8 XXX + SG_ INCREMENTING_ACCEL_PEDAL : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_ACCEL_PEDAL : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_PEDAL : 35|1@0+ (1,0) [0|1] "" XXX + +BO_ 464 SEATBELT_STATUS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 13|1@0+ (1,0) [0|1] "" XXX + +BO_ 544 LKAS_INDICATOR_1: 8 XXX + SG_ LKAS_IS_GREEN : 23|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_1 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_2 : 51|1@1+ (1,0) [0|1] "" XXX + SG_ INCREMENTING_220 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_220 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_220_2 : 34|11@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_220_1 : 19|12@0+ (1,0) [0|4095] "" XXX + SG_ UNKNOWN_220_0 : 2|11@0+ (1,0) [0|63] "" XXX + +BO_ 658 LKAS_INDICATOR_2: 6 XXX + SG_ LKAS_INCREMENTING : 39|4@0+ (1,0) [0|15] "" XXX + SG_ LKAS_CHECKSUM_2 : 40|8@1+ (1,0) [0|255] "" XXX + SG_ LKAS_STEERING_TORQUE_MAYBE : 3|12@0- (1,0) [0|63] "" XXX + +BO_ 678 LKAS_INDICATOR_3: 8 XXX + SG_ WARNING_PLACE_HANDS : 22|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_WHITE_OR_YELLOW : 0|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_IS_YELLOW_2 : 19|1@1+ (1,0) [0|1] "" XXX + +BO_ 705 AUTO_PARK_BUTTON: 8 XXX + SG_ AUTO_PARK_TOGGLE_2 : 8|1@1+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_TOGGLE_1 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ INCREASING_UNKNOWN : 32|7@1+ (1,0) [0|15] "" XXX + +BO_ 719 AUTO_PARK_SIGNALS_1: 8 XXX + SG_ AUTO_PARK_UNKNOWN_1 : 7|16@0+ (1,0) [0|31] "" XXX + +BO_ 671 AUTO_PARK_SIGNALS_2: 8 XXX + SG_ AUTO_PARK_PARALLEL : 21|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_PERPENDICULAR_1 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ INCREMENTING : 55|4@0+ (1,0) [0|15] "" XXX + SG_ AUTO_PARK_CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_MAYBE_TURNING : 3|12@0+ (1,0) [0|1023] "" XXX + SG_ AUTO_PARK_TURNING_STATUS : 7|4@0+ (1,0) [0|15] "" XXX + +BO_ 784 AUTO_PARK_LESS_INTERESTING: 8 XXX + SG_ INCREASING_UNKNOWN : 48|8@1+ (1,0) [0|7] "" XXX + SG_ AUTO_PARK_PERPENDICULAR_2 : 61|1@0+ (1,0) [0|255] "" XXX + +BO_ 826 AUTO_PARK_SIGNALS_3: 8 XXX + SG_ AUTO_PARK_HAS_CONTROL_3 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HUMAN_HAS_CONTROL : 2|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_GEAR_1 : 27|4@0+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_GEAR_2 : 32|4@1+ (1,0) [0|15] "" XXX + SG_ AUTO_PARK_GEAR_3 : 48|4@1+ (1,0) [0|15] "" XXX + +BO_ 332 STEERING_2: 8 XXX + SG_ INCREMENTING_14C : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ENERGY_RELATED : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ STEER_ANGLE_2 : 7|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX + +BO_ 720 BLIND_SPOT_WARNINGS: 6 XXX + SG_ BLIND_SPOT_RIGHT : 5|1@0+ (1,0) [0|1] "" XXX + SG_ BLIND_SPOT_LEFT : 2|1@1+ (1,0) [0|1] "" XXX + +BO_ 331 BRAKE_3: 8 XXX + SG_ BRAKE_RELATED_3 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ INCREMENTING_14B : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_14B : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 PARKSENSE_SIGNAL: 8 XXX + SG_ PARKSENSE_DISABLED : 34|1@0+ (1,0) [0|1] "" XXX + SG_ INCREMENTING_260 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_260 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ IN_REVERSE : 10|1@1+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_1 : 16|1@1+ (1,0) [0|255] "" XXX + SG_ HUMAN_HAS_CONTROL : 17|1@1+ (1,0) [0|3] "" XXX + +BO_ 729 LKAS_STATUS_1: 5 XXX + SG_ LKAS_STATUS_OK : 31|16@0+ (1,0) [0|65535] "" XXX + +BO_ 274 NEW_MSG_112: 2 XXX + +BO_ 290 NEW_MSG_122: 6 XXX + +BO_ 376 NEW_MSG_178: 3 XXX + +BO_ 288 ACCEL_RELATED_120: 7 XXX + SG_ UNKNOWN_INCREMENTING_120 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ UNKNOWN_CHECKSUM_120 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL : 16|8@1+ (1,0) [0|255] "" XXX + SG_ GAS_ENGINE_RPM_MAYBE : 31|16@0+ (1,0) [0|65535] "" XXX + +BO_ 257 ACCEL_RELATED_101: 5 XXX + SG_ ENERGY_OR_RPM : 24|8@1+ (1,0) [0|255] "" XXX + +BO_ 388 NEW_MSG_184: 4 XXX + +BO_ 448 NEW_MSG_1c0: 6 XXX + +BO_ 456 NEW_MSG_1c8: 4 XXX + +BO_ 560 NEW_MSG_230: 4 XXX + +BO_ 564 NEW_MSG_234: 4 XXX + +BO_ 571 WHEEL_BUTTONS: 3 XXX + SG_ CHECKSUM_23B : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ACC_FOLLOW_DEC : 1|1@1+ (1,0) [0|3] "" XXX + SG_ ACC_SPEED_INC : 2|1@0+ (1,0) [0|255] "" XXX + SG_ ACC_SPEED_DEC : 3|1@1+ (1,0) [0|3] "" XXX + SG_ ACC_FOLLOW_INC : 8|1@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX + +BO_ 669 NEW_MSG_29d: 3 XXX + SG_ INCREMENTING_29D : 15|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_29D : 16|8@1+ (1,0) [0|255] "" XXX + +BO_ 825 NEW_MSG_339: 2 XXX + +BO_ 856 NEW_MSG_358: 4 XXX + +BO_ 860 NEW_MSG_35c: 6 XXX + +BO_ 924 NEW_MSG_39c: 3 XXX + +BO_ 969 NEW_MSG_3c9: 4 XXX + +BO_ 974 NEW_MSG_3ce: 5 XXX + +BO_ 993 NEW_MSG_3e1: 7 XXX + +BO_ 838 NEW_MSG_346: 2 XXX + +BO_ 926 NEW_MSG_39e: 3 XXX + +BO_ 168 ACCEL_RELATED_a8: 8 XXX + SG_ ACCEL_RELATED : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ INCREMENTING_A8 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_A8 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 270 ACCEL_RELATED_10e: 8 XXX + SG_ ACCEL_OR_RPM : 7|16@0+ (1,0) [0|255] "" XXX + SG_ INCREMENTING_ACCEL : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_ACCEL : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ELECTRIC_MOTOR : 23|16@0+ (1,0) [0|65535] "" XXX + +BO_ 291 ENERGY_RELATED_123: 8 XXX + SG_ ENERGY_GAIN_LOSS : 18|11@0- (1,0) [0|255] "" XXX + SG_ INCREMENTING_123 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_123 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ENERGY_SMOOTHER_CURVE : 35|12@0+ (1,0) [0|2047] "" XXX + +BO_ 294 ENERGY_RELATED_126: 8 XXX + SG_ CHECKSUM_126 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_126_1 : 3|12@0+ (1,0) [0|4095] "" XXX + SG_ INCREMENTING_126 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ UNKNOWN_126_2 : 35|12@0+ (1,0) [0|4095] "" XXX + SG_ ENERGY_GAIN_LOSS_NOISY : 19|12@0+ (1,0) [0|2047] "" XXX + +BO_ 300 NEW_MSG_12C: 8 XXX + +BO_ 308 ACCEL_GAS_134: 8 XXX + SG_ INCREMENTING_134 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ACCEL_134 : 40|4@1+ (1,0) [0|15] "" XXX + +BO_ 532 ENERGY_RELATED_214: 8 XXX + SG_ NOISY_SLOWLY_DECREASING : 16|9@0+ (1,0) [0|255] "" XXX + SG_ ENERGY_RELATED : 0|9@0+ (1,0) [0|255] "" XXX + +BO_ 559 ACCEL_GAS_22F: 8 XXX + SG_ ACCEL_22F : 0|4@1+ (1,0) [0|255] "" XXX + SG_ INCREMENTING_22F : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_22F : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 655 CHARGING_MAYBE_28F: 8 XXX + SG_ CHARGING : 0|2@1+ (1,0) [0|3] "" XXX + +BO_ 660 BRAKE_RELATED_294: 8 XXX + SG_ INCREMENTING_294 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_294 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PERHAPS_294 : 24|8@1+ (1,0) [0|255] "" XXX + +BO_ 764 ACCEL_RELATED_2FC: 8 XXX + SG_ ACCEL_2FC : 8|6@1+ (1,0) [0|255] "" XXX + +BO_ 816 TRACTION_BUTTON: 8 XXX + SG_ TRACTION_OFF : 19|1@1+ (1,0) [0|3] "" XXX + +BO_ 878 ACCEL_RELATED_36E: 8 XXX + SG_ ACCEL_OR_RPM_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_OR_RPM_1 : 0|8@1+ (1,0) [0|255] "" XXX + +BO_ 324 SPEED_2: 8 XXX + SG_ SPEED_2 : 31|16@0+ (0.01,0) [0|255] "m/s" XXX + +BO_ 501 DASHBOARD: 8 XXX + SG_ ACC_SPEED_CONFIG_KPH : 15|8@0+ (1,0) [0|3] "km/h" XXX + SG_ ACC_SPEED_CONFIG_MPH : 23|8@0+ (1,0) [0|3] "mph" XXX + SG_ ACC_DISTANCE_CONFIG_1 : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ACC_DISTANCE_CONFIG_2 : 41|2@0+ (1,0) [0|3] "" XXX + SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" XXX + +BO_ 639 NEW_MSG_27f: 8 XXX + SG_ INCREASING : 40|8@1+ (1,0) [0|255] "" XXX + +BO_ 701 NEW_MSG_2bd: 8 XXX + SG_ unknown_1 : 32|8@1+ (1,0) [0|255] "" XXX + +BO_ 832 UNKNOWN_340: 8 XXX + SG_ SPEED_DIGITAL : 56|8@1+ (1,0) [0|255] "mph" XXX + +BO_ 848 UNKNOWN_350: 8 XXX + SG_ INCREASING_LSB : 0|6@1+ (1,0) [0|255] "" XXX + SG_ INCREASING_MSB : 12|5@0+ (1,0) [0|31] "" XXX + +BO_ 908 NEW_MSG_38c: 8 XXX + SG_ INCREASING_MSB : 44|5@0+ (1,0) [0|31] "" XXX + SG_ INCREASING_LSB : 56|6@1+ (1,0) [0|255] "" XXX + +BO_ 938 NEW_MSG_3aa: 8 XXX + SG_ INCREASING_UNKNOWN_1 : 32|8@1+ (1,0) [0|255] "" XXX + SG_ INCREASING_UNKNOWN_2 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 940 NEW_MSG_3ac: 8 XXX + SG_ INCREASING_1 : 32|4@1+ (1,0) [0|15] "" XXX + SG_ INCREASING_2 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 941 NEW_MSG_3ad: 8 XXX + SG_ INCREASING_1 : 32|5@1+ (1,0) [0|31] "" XXX + SG_ INCREASING_2 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 500 ACC_2: 8 XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ACC_STATUS_1 : 7|3@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_MAYBE : 18|11@0+ (1,0) [0|255] "" XXX + SG_ ACC_STATUS_2 : 21|3@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_BOOL_1 : 36|1@0+ (1,0) [0|3] "" XXX + +BO_ 625 ACC_1: 8 XXX + SG_ SPEED : 24|8@1+ (1,0) [0|255] "km/h" XXX + SG_ ACCEL_PERHAPS : 39|16@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + +BO_ 268 ACC_10c: 8 XXX + SG_ BRAKE_PERHAPS : 48|1@1+ (1,0) [0|3] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 384 NEW_MSG_180: 8 XXX + SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 32|8@1+ (1,0) [0|3] "" XXX + +BO_ 853 NEW_MSG_355: 8 XXX + +BO_ 939 NEW_MSG_3ab: 8 XXX + +BO_ 512 NEW_MSG_200: 8 XXX + SG_ NEW_SIGNAL_1 : 16|8@1+ (1,0) [0|255] "" XXX + SG_ INCREASING : 27|12@0+ (1,0) [0|127] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + + + + +CM_ SG_ 258 UNKNOWN_STEERING "never goes above 4. see if human-applied torque"; +CM_ SG_ 258 STEER_ANGLE "positive is left (counter-clockwise)"; +CM_ SG_ 514 SPEED_LEFT "TODO find upper limit"; +CM_ SG_ 653 BRAKE_PRESSURE "max seems to be 148"; +CM_ SG_ 820 TURN_LIGHT_LEFT "oscillates with the light blinking"; +CM_ SG_ 820 TURN_LIGHT_RIGHT "hazard blinks both right and left lights"; +CM_ SG_ 746 PRNDL "4=D, 3=N, 2=R, 1=P"; +CM_ SG_ 746 GEAR_CHECKSUM "different than the LKAS checksum. unknown non-simple algorithm. just build a lookup table for it."; +CM_ SG_ 284 SPEED_RELATED_1 "Another Speed Signal, Maybe RPMs?"; +CM_ SG_ 284 BRAKE_RELATED_1_1 "Correlates with braking"; +CM_ SG_ 320 BRAKE_PRESSED_2 "Value is 5 when brake is pressed by human, 1 when ACC brake"; +CM_ SG_ 320 BRAKE_PRESSED_ACC "set when ACC brakes"; +CM_ SG_ 792 TURN_SIGNALS "1=Left, 2=Right"; +CM_ SG_ 792 HIGH_BEAM_FLASH "use this for genericToggle"; +CM_ SG_ 264 ACCEL_PEDAL "not in ACC so seems to be actual pedal. Use for gasPressed"; +CM_ SG_ 544 AUTO_PARK_HAS_CONTROL_1 "set when autopark has control"; +CM_ SG_ 658 LKAS_INCREMENTING "each message increments, 0..f"; +CM_ SG_ 658 LKAS_CHECKSUM_2 "checksum calculated with https://gist.github.com/adhintz/94bf8d19b9075539f50172ab0fb24ba1"; +CM_ SG_ 658 LKAS_STEERING_TORQUE_MAYBE "1024 is straight. most sent by stock system is 1024+-230. + is left. typically changes by 2 or 3 each 0.01s"; +CM_ SG_ 678 WARNING_PLACE_HANDS "set when warning displays place hands on steering wheel"; +CM_ SG_ 678 LKAS_WHITE_OR_YELLOW "set when indicator is yellow or white. could indicate lkas not on track."; +CM_ SG_ 678 LKAS_IS_YELLOW_2 "set when indicator is yellow. could indicate lkas is steering."; +CM_ SG_ 705 AUTO_PARK_TOGGLE_1 "set briefly when turning on or off self-parking"; +CM_ SG_ 705 INCREASING_UNKNOWN "sometimes decreasing"; +CM_ SG_ 671 AUTO_PARK_PARALLEL "parallel parking mode"; +CM_ SG_ 671 AUTO_PARK_PERPENDICULAR_1 "perpendicular parking mode"; +CM_ SG_ 671 AUTO_PARK_MAYBE_TURNING "something with autopark turning the steering wheel maybe."; +CM_ SG_ 671 AUTO_PARK_TURNING_STATUS "0 when not steering. when steering starts, 4 for two packets, and then 5 for the rest"; +CM_ SG_ 784 INCREASING_UNKNOWN "perhaps distance traveled"; +CM_ SG_ 826 AUTO_PARK_GEAR_1 "Reverse=0, Forward=f"; +CM_ SG_ 826 AUTO_PARK_GEAR_2 "Reverse=0, Forward=f"; +CM_ SG_ 826 AUTO_PARK_GEAR_3 "Reverse=0, Forward=f"; +CM_ SG_ 332 STEER_ANGLE_2 "slightly lags the other steer_angle signal. also more noisy."; +CM_ SG_ 720 BLIND_SPOT_RIGHT "yellow triangle alert on side view mirror when a car is in your blind spot"; +CM_ SG_ 608 PARKSENSE_DISABLED "set if parksense is disabled"; +CM_ SG_ 729 LKAS_STATUS_OK "Set to 0x0820 when LKAS system is plugged in."; +CM_ SG_ 288 UNKNOWN_CHECKSUM_120 "not the LKAS checksum"; +CM_ SG_ 288 GAS_ENGINE_RPM_MAYBE "lags acceleration, perhaps gas engine"; +CM_ SG_ 257 ENERGY_OR_RPM "perhaps energy consumption or RPMs"; +CM_ SG_ 270 ELECTRIC_MOTOR "0x7fff indicates electric motor not in use"; +CM_ SG_ 291 ENERGY_GAIN_LOSS "unsure what this actually is"; +CM_ SG_ 291 ENERGY_SMOOTHER_CURVE "unusre what it is, but smoother"; +CM_ SG_ 532 NOISY_SLOWLY_DECREASING "perhaps battery but do not know"; +CM_ SG_ 816 TRACTION_OFF "set when traction off button is enabled"; +CM_ SG_ 324 SPEED_2 "signal is approx half other speeds"; +CM_ SG_ 501 ACC_SPEED_CONFIG_KPH "speed configured for ACC"; +CM_ SG_ 501 ACC_SPEED_CONFIG_MPH "speed configured for ACC"; +CM_ SG_ 639 INCREASING "perhaps number of seconds divided by two for this drive"; +CM_ SG_ 848 INCREASING_LSB "lower part of time counter"; +CM_ SG_ 848 INCREASING_MSB "upper part of time counter"; +CM_ SG_ 908 INCREASING_MSB "time based"; +CM_ SG_ 500 ACC_STATUS_1 "2 briefly (9 packets) when ACC goes to green, 1 help when ACC coming to a stop and at a stop"; +CM_ SG_ 500 BRAKE_MAYBE "2046 in non-ACC and non-decel. Signal on deceleration. 818 for already stopped break."; +CM_ SG_ 500 ACC_STATUS_2 "set to 1 in non-ACC, 3 when ACC enabled (white icon), and 7 when ACC in use (green icon)"; +CM_ SG_ 500 BRAKE_BOOL_1 "set to 1 when ACC decel. 0 on non-ACC and accel."; +CM_ SG_ 625 SPEED "zero on non-acc drives"; +CM_ SG_ 625 ACCEL_PERHAPS "set to 7767 on non-ACC drives. ACC drive 40k is constant speed, 42k is accelerating"; +CM_ SG_ 268 BRAKE_PERHAPS "triggers only on ACC braking"; +CM_ SG_ 384 NEW_SIGNAL_1 "set in ACC gas driving. not set in electric human. not sure about gas human driving."; +VAL_ 746 PRNDL 4 "Drive" 3 "Neutral" 2 "Reverse" 1 "Park" ; +VAL_ 792 TURN_SIGNALS 2 "Right" 1 "Left" ; diff --git a/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc b/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc new file mode 100644 index 00000000000000..0c5d01c79deec4 --- /dev/null +++ b/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc @@ -0,0 +1,230 @@ +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_: XXX + + +BO_ 544 a_1: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 576 b_1: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 a_2: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 640 b_2: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 644 a_3: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 648 b_3: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 652 a_4: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 656 b_4: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 512 unknown_200: 8 XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ increasing : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros_0 : 3|12@0+ (1,0) [0|63] "" XXX + SG_ zeros_1 : 47|12@0+ (1,0) [0|63] "" XXX + SG_ status0 : 7|4@0+ (1,0) [0|15] "" XXX + SG_ unknown_0 : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 514 unknown_202: 8 XXX + SG_ COUNTER : 43|4@0+ (1,0) [0|15] "" XXX + SG_ sig3 : 31|8@0+ (1,0) [0|65535] "" XXX + SG_ increasing : 39|12@0+ (1,0) [0|15] "" XXX + +BO_ 706 c_1: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + +BO_ 708 c_2: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 710 c_3: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 712 c_4: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 714 c_5: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 716 c_6: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 718 c_7: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 720 c_8: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 722 c_9: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 724 c_10: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 674 d_1: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 676 d_2: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 678 d_3: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 680 d_4: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 682 d_5: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 684 d_6: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 686 d_7: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 688 d_8: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 690 d_9: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 692 d_10: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 672 NEW_MSG_5: 8 XXX + SG_ NEW_SIGNAL_1 : 9|10@0+ (1,0) [0|1023] "" XXX + SG_ NEW_SIGNAL_2 : 45|10@0+ (1,0) [0|1023] "" XXX + + + + +CM_ SG_ 544 track_id "for message a_1 track_id is always 1, similar for other messages and track_id"; +CM_ SG_ 544 REL_ACCEL "perhaps REL_ACCEL because it responds faster and before REL_SPEED"; +CM_ SG_ 544 sig2 "perhaps distance to object. LONG_DIST or REL_ACCEL or REL_SPEED"; +CM_ SG_ 576 zeros "not always zero, sometimes has value when another car changes lanes"; +CM_ SG_ 706 LAT_DIST "positive is to the right, negative is to the left"; diff --git a/opendbc/ford_fusion_2018_adas.dbc b/opendbc/ford_fusion_2018_adas.dbc new file mode 100644 index 00000000000000..63a0b9909c3c3b --- /dev/null +++ b/opendbc/ford_fusion_2018_adas.dbc @@ -0,0 +1,419 @@ +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_ + +BU_: XXX + +BO_ 1280 Object_00: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1281 Object_01: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1282 Object_02: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1283 Object_03: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1284 Object_04: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1285 Object_05: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1286 Object_06: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1287 Object_07: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1288 Object_08: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1289 Object_09: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1290 Object_10: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1291 Object_11: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1292 Object_12: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1293 Object_13: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1294 Object_14: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1295 Object_15: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1296 Object_16: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1297 Object_17: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1298 Object_18: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1299 Object_19: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1300 Object_20: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1301 Object_21: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1302 Object_22: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1303 Object_23: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1304 Object_24: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1305 Object_25: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1306 Object_26: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1307 Object_27: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1308 Object_28: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1309 Object_29: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1310 Object_30: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1311 Object_31: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1312 Object_32: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1313 Object_33: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1314 Object_34: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1315 Object_35: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1316 Object_36: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1317 Object_37: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1318 Object_38: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1319 Object_39: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1320 Object_40: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1321 Object_41: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1322 Object_42: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1323 Object_43: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1324 Object_44: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1325 Object_45: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1326 Object_46: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1327 Object_47: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1328 Object_48: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1329 Object_49: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1330 Object_50: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1331 Object_51: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1332 Object_52: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1333 Object_53: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1334 Object_54: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1335 Object_55: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1336 Object_56: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1337 Object_57: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1338 Object_58: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1339 Object_59: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1340 Object_60: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1341 Object_61: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1342 Object_62: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + +BO_ 1343 Object_63: 8 XXX + SG_ X_Rel : 18|11@0+ (0.1,0) [0|0] "m" XXX + SG_ V_Rel : 52|13@0- (0.01,0) [0|0] "m/s" XXX + SG_ A_Rel : 33|10@0- (0.05,0) [0|0] "m/s2" XXX + SG_ Angle : 12|10@0- (-0.1,0) [0|0] "deg" XXX + diff --git a/opendbc/ford_fusion_2018_pt.dbc b/opendbc/ford_fusion_2018_pt.dbc new file mode 100644 index 00000000000000..1667a360b529d6 --- /dev/null +++ b/opendbc/ford_fusion_2018_pt.dbc @@ -0,0 +1,136 @@ +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_ + +BU_: XXX + +BO_ 130 EPAS_INFO: 8 XXX + SG_ SteMdule_U_Meas : 39|8@0+ (0.05,6.0) [0|0] "Volts" XXX + SG_ SteMdule_I_Est : 21|12@0+ (0.05,-64.0) [0|0] "Amps" XXX + SG_ EPAS_FAILURE : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SteeringColumnTorque : 7|8@0+ (0.0625,-8.0) [0|0] "Nm" XXX + SG_ SAPPAngleControlStat6 : 15|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat5 : 14|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat4 : 13|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat3 : 12|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat2 : 11|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat1 : 23|2@0+ (1,0) [0|0] "" XXX + +BO_ 118 Steering_Wheel_Data_CG1: 8 XXX + SG_ SteWhlRelInit_An_Sns : 6|15@0+ (0.1,-1600.0) [0|0] "deg" XXX + SG_ SteWhlRelCalib_An_Sns : 23|15@0+ (0.1,-1600.0) [0|0] "deg" XXX + SG_ SteWhlRelInit2_An_Sns : 55|16@0+ (0.1,-3200.0) [0|0] "deg" XXX + SG_ SteWhlAn_No_Cs : 39|8@0+ (1,0) [0|0] "" XXX + SG_ SteWhlAn_No_Cnt : 47|4@0+ (1,0) [0|0] "Counts" XXX + +BO_ 131 Steering_Buttons: 8 XXX + SG_ Right_Turn_Light : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Left_Turn_Light : 4|1@0+ (1,0) [0|0] "" XXX + SG_ Dist_Decr : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Dist_Incr : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Cancel : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Resume : 29|1@0+ (1,0) [0|0] "" XXX + SG_ Set : 28|1@0+ (1,0) [0|0] "" XXX + SG_ Main : 38|1@0+ (1,0) [0|0] "" XXX + +BO_ 145 Yaw_Data: 8 XXX + SG_ VehYaw_W_Actl : 39|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + SG_ VehRol_W_Actl : 23|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + SG_ VehPtch_W_Actl : 7|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + +BO_ 146 Accel_Data: 8 XXX + SG_ VehVertAActl_D_Qf : 38|2@0+ (1,0) [0|0] "" XXX + SG_ VehLongAActl_D_Qf : 22|2@0+ (1,0) [0|0] "" XXX + SG_ VehLatAActl_D_Qf : 6|2@0+ (1,0) [0|0] "" XXX + SG_ VehVert_A_Actl : 36|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + SG_ VehLong_A_Actl : 20|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + SG_ VehLat_A_Actl : 4|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + +BO_ 357 Cruise_Status: 8 XXX + SG_ Brake_Drv_Appl : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Cruise_State : 11|4@0+ (1,0) [0|0] "" XXX + SG_ Set_Speed : 23|8@0+ (1,0) [0|0] "" XXX + +BO_ 516 EngineData_14: 8 XXX + SG_ ApedPosScal_Pc_Actl : 1|10@0+ (0.1,0) [0|0] "%" XXX + +BO_ 535 WheelSpeed_CG1: 8 XXX + SG_ WhlRr_W_Meas : 55|14@0+ (0.04,0) [0|0] "rad/s" XXX + SG_ WhlRl_W_Meas : 39|14@0+ (0.04,0) [0|0] "rad/s" XXX + SG_ WhlFr_W_Meas : 23|14@0+ (0.04,0) [0|0] "rad/s" XXX + SG_ WhlFl_W_Meas : 7|14@0+ (0.04,0) [0|0] "rad/s" XXX + +BO_ 534 WheelData: 8 XXX + SG_ WhlRotatRr_No_Cnt : 23|8@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRr_D_Actl : 33|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRl_D_Actl : 39|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFr_D_Actl : 37|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFl_D_Actl : 35|2@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatRl_No_Cnt : 31|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFr_No_Cnt : 7|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFl_No_Cnt : 15|8@0+ (1,0) [0|0] "" XXX + SG_ WHEEL_ROLLING_TIMESTAMP : 47|8@0+ (1,0) [0|0] "" XXX + +BO_ 947 Doors: 8 XXX + SG_ Door_FL_Open : 61|1@0+ (1,0) [0|0] "" XXX + SG_ Door_FR_Open : 60|1@0+ (1,0) [0|0] "" XXX + SG_ Door_RL_Open : 48|1@0+ (1,0) [0|0] "" XXX + SG_ Door_RR_Open : 49|1@0+ (1,0) [0|0] "" XXX + +BO_ 963 BCM_to_HS_Body: 8 XXX + SG_ Brake_Lights : 8|1@0+ (1,0) [0|0] "" XXX + +BO_ 970 Lane_Keep_Assist_Control: 8 XXX + SG_ Lkas_Action : 7|4@0+ (1,0) [0|15] "" XXX + SG_ Lkas_Alert : 3|4@0+ (1,0) [0|15] "" XXX + SG_ Lane_Curvature : 15|12@0+ (5e-06,-0.01) [0|0] "1/m" XXX + SG_ Steer_Angle_Req : 19|12@0+ (0.04297,-88.00445) [0|0] "deg" XXX + +BO_ 972 Lane_Keep_Assist_Status: 8 XXX + SG_ LaHandsOff_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + SG_ LaActDeny_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + SG_ LaActAvail_D_Actl : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 984 Lane_Keep_Assist_Ui: 8 XXX + SG_ Set_Me_X80 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ Set_Me_X45 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ Lines_Hud : 55|4@0+ (1,0) [0|15] "" XXX + SG_ Hands_Warning_W_Chime : 50|1@0+ (1,0) [0|1] "" XXX + SG_ Hands_Warning : 49|1@0+ (1,0) [0|1] "" XXX + SG_ Set_Me_X30 : 63|8@0+ (1,0) [0|255] "" XXX + +VAL_ 357 Cruise_State 4 "active" 3 "standby" 0 "off" ; +VAL_ 970 Lkas_Action 15 "off" 9 "abrupt" 8 "abrupt2" 5 "smooth" 4 "smooth2" ; +VAL_ 970 Lkas_Alert 15 "no_alert" 3 "high_intensity" 2 "mid_intensity" 1 "low_intensity" ; +VAL_ 972 LaActAvail_D_Actl 3 "available" 2 "tbd" 1 "not_available" 0 "fault" ; +VAL_ 984 Lines_Hud 15 "none" 11 "grey_yellow" 8 "green_red" 7 "yellow_grey" 6 "grey_grey" 4 "red_green" 3 "green_green" ; +CM_ SG_ 970 Lkas_Action "only vals 4, 5, 8, 9 seem to work. 4 and 5 are a bit smoother" ; diff --git a/opendbc/generator/generator.py b/opendbc/generator/generator.py new file mode 100755 index 00000000000000..85f3f009e27d02 --- /dev/null +++ b/opendbc/generator/generator.py @@ -0,0 +1,49 @@ +#!/usr/bin/env python2 +import os +import re + +cur_path = os.path.dirname(os.path.realpath(__file__)) +generator_path = os.path.join(cur_path, '../') +include_pattern = re.compile(r'CM_ "IMPORT (.*?)"') + + +def read_dbc(dir_name, filename): + with open(os.path.join(dir_name, filename)) as file_in: + return file_in.read() + + +def create_dbc(dir_name, filename): + dbc_file_in = read_dbc(dir_name, filename) + + includes = include_pattern.findall(dbc_file_in) + + output_filename = filename.replace('.dbc', '_generated.dbc') + output_file_location = os.path.join(generator_path, output_filename) + + with open(output_file_location, 'w') as dbc_file_out: + dbc_file_out.write('CM_ "AUTOGENERATED FILE, DO NOT EDIT"\n') + + for include_filename in reversed(includes): + include_file_header = '\n\nCM_ "Imported file %s starts here"\n' % include_filename + dbc_file_out.write(include_file_header) + + include_file = read_dbc(dir_name, include_filename) + dbc_file_out.write(include_file) + + dbc_file_out.write('\nCM_ "%s starts here"\n' % filename) + + core_dbc = include_pattern.sub('', dbc_file_in) + dbc_file_out.write(core_dbc) + + +for dir_name, _, filenames in os.walk(cur_path): + if dir_name == cur_path: + continue + + print dir_name + for filename in filenames: + if filename.startswith('_'): + continue + + print filename + create_dbc(dir_name, filename) diff --git a/opendbc/generator/honda/_bosch_2018.dbc b/opendbc/generator/honda/_bosch_2018.dbc new file mode 100644 index 00000000000000..0b8d8a17f02c9e --- /dev/null +++ b/opendbc/generator/honda/_bosch_2018.dbc @@ -0,0 +1,263 @@ +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_ + +BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 330 STEERING_SENSORS: 8 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_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX + SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM + SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + + BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 804 CRUISE: 8 PCM + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; \ No newline at end of file diff --git a/opendbc/generator/honda/_comma.dbc b/opendbc/generator/honda/_comma.dbc new file mode 100644 index 00000000000000..0be2275381eb92 --- /dev/null +++ b/opendbc/generator/honda/_comma.dbc @@ -0,0 +1,15 @@ +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; diff --git a/opendbc/generator/honda/_honda_2017.dbc b/opendbc/generator/honda/_honda_2017.dbc new file mode 100644 index 00000000000000..82818f142ad504 --- /dev/null +++ b/opendbc/generator/honda/_honda_2017.dbc @@ -0,0 +1,205 @@ +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; diff --git a/opendbc/generator/honda/acura_ilx_2016_can.dbc b/opendbc/generator/honda/acura_ilx_2016_can.dbc new file mode 100644 index 00000000000000..50677c4b023061 --- /dev/null +++ b/opendbc/generator/honda/acura_ilx_2016_can.dbc @@ -0,0 +1,77 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/acura_rdx_2018_can.dbc b/opendbc/generator/honda/acura_rdx_2018_can.dbc new file mode 100644 index 00000000000000..30d09c7dbb5d39 --- /dev/null +++ b/opendbc/generator/honda/acura_rdx_2018_can.dbc @@ -0,0 +1,65 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 392 GEARBOX: 6 XXX + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX + SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" EON + SG_ GEAR : 36|5@0+ (1,0) [0|31] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ PARKING_BRAKE_LIGHT : 2|1@0+ (1,0) [0|1] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 422 PARKING_BRAKE_LIGHT "Believe this is just the dash light for the parking break"; +VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; +VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_accord_lx15t_2018_can.dbc b/opendbc/generator/honda/honda_accord_lx15t_2018_can.dbc new file mode 100644 index 00000000000000..9e95f56dbb51be --- /dev/null +++ b/opendbc/generator/honda/honda_accord_lx15t_2018_can.dbc @@ -0,0 +1,52 @@ +CM_ "IMPORT _bosch_2018.dbc" + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ BOH : 40|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_accord_s2t_2018_can.dbc b/opendbc/generator/honda/honda_accord_s2t_2018_can.dbc new file mode 100644 index 00000000000000..e0a7ff328f6282 --- /dev/null +++ b/opendbc/generator/honda/honda_accord_s2t_2018_can.dbc @@ -0,0 +1,48 @@ +CM_ "IMPORT _bosch_2018.dbc" + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ BOH : 40|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc b/opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc new file mode 100644 index 00000000000000..2de149ad5d0993 --- /dev/null +++ b/opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc @@ -0,0 +1,55 @@ +CM_ "IMPORT _bosch_2018.dbc" + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_civic_touring_2016_can.dbc b/opendbc/generator/honda/honda_civic_touring_2016_can.dbc new file mode 100644 index 00000000000000..21327ec3925b0a --- /dev/null +++ b/opendbc/generator/honda/honda_civic_touring_2016_can.dbc @@ -0,0 +1,143 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 148 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 330 STEERING_SENSORS: 8 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_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 6 XXX + SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 450 EPB_STATE "3 \"engaged\" 2 \"disengaging\" 1 \"engaging\" 0 \"disengaged\""; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_crv_ex_2017_can.dbc b/opendbc/generator/honda/honda_crv_ex_2017_can.dbc new file mode 100644 index 00000000000000..e8cc456bfcb8b0 --- /dev/null +++ b/opendbc/generator/honda/honda_crv_ex_2017_can.dbc @@ -0,0 +1,66 @@ +CM_ "IMPORT _bosch_2018.dbc" + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 344 DISTANCE_COUNTER ""; +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; +CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; +CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; + +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_crv_touring_2016_can.dbc b/opendbc/generator/honda/honda_crv_touring_2016_can.dbc new file mode 100644 index 00000000000000..f75586a4c5820a --- /dev/null +++ b/opendbc/generator/honda/honda_crv_touring_2016_can.dbc @@ -0,0 +1,75 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_fit_ex_2018_can.dbc b/opendbc/generator/honda/honda_fit_ex_2018_can.dbc new file mode 100644 index 00000000000000..bc911ffcb696c3 --- /dev/null +++ b/opendbc/generator/honda/honda_fit_ex_2018_can.dbc @@ -0,0 +1,97 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_odyssey_exl_2018.dbc b/opendbc/generator/honda/honda_odyssey_exl_2018.dbc new file mode 100644 index 00000000000000..6c181d877b95be --- /dev/null +++ b/opendbc/generator/honda/honda_odyssey_exl_2018.dbc @@ -0,0 +1,114 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + +BO_ 450 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_pilot_touring_2017_can.dbc b/opendbc/generator/honda/honda_pilot_touring_2017_can.dbc new file mode 100644 index 00000000000000..a499b6bc9af4a0 --- /dev/null +++ b/opendbc/generator/honda/honda_pilot_touring_2017_can.dbc @@ -0,0 +1,67 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc b/opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc new file mode 100644 index 00000000000000..7eee6a6c0205a2 --- /dev/null +++ b/opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc @@ -0,0 +1,62 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/toyota/_comma.dbc b/opendbc/generator/toyota/_comma.dbc new file mode 100644 index 00000000000000..4e4c82d80e7c71 --- /dev/null +++ b/opendbc/generator/toyota/_comma.dbc @@ -0,0 +1,25 @@ +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; diff --git a/opendbc/toyota_rav4_hybrid_2017_pt.dbc b/opendbc/generator/toyota/_toyota_2017.dbc similarity index 60% rename from opendbc/toyota_rav4_hybrid_2017_pt.dbc rename to opendbc/generator/toyota/_toyota_2017.dbc index e32171cedc6b25..294b948ddef737 100644 --- a/opendbc/toyota_rav4_hybrid_2017_pt.dbc +++ b/opendbc/generator/toyota/_toyota_2017.dbc @@ -40,6 +40,11 @@ BO_ 36 KINEMATICS: 8 XXX SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + BO_ 166 BRAKE: 8 XXX SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX @@ -57,15 +62,17 @@ BO_ 180 SPEED: 8 XXX BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 552 ACCELEROMETER: 8 XXX SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX @@ -74,38 +81,25 @@ BO_ 552 ACCELEROMETER: 8 XXX BO_ 560 BRAKE_MODULE2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX -BO_ 581 GAS_PEDAL: 8 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 643 PRE_COLLISION: 8 XXX -BO_ 740 STEERING_LKA: 8 XXX +BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX BO_ 742 LEAD_INFO: 8 DSU SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU @@ -114,49 +108,49 @@ 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 - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 921 PCM_CRUISE_SM: 8 XXX SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX BO_ 951 ESP_CONTROL: 8 ESP SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX BO_ 1042 LKAS_HUD: 8 XXX SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX BO_ 1553 UI_SEETING: 8 XXX SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX BO_ 1568 SEATS_DOORS: 8 XXX SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX @@ -165,39 +159,98 @@ BO_ 1568 SEATS_DOORS: 8 XXX SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX CM_ SG_ 36 ACCEL_Y "unit is tbd"; CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; -VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 50 "temporary_fault"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ; +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"; VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; diff --git a/opendbc/generator/toyota/lexus_is_2018_pt.dbc b/opendbc/generator/toyota/lexus_is_2018_pt.dbc new file mode 100644 index 00000000000000..6548822fddca9c --- /dev/null +++ b/opendbc/generator/toyota/lexus_is_2018_pt.dbc @@ -0,0 +1,39 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +BO_ 1009 PCM_CRUISE_3: 8 XXX + SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX + SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc b/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc new file mode 100644 index 00000000000000..8fe5ec1991f18a --- /dev/null +++ b/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc @@ -0,0 +1,33 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 5 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/opendbc/generator/toyota/toyota_avalon_2017_pt.dbc b/opendbc/generator/toyota/toyota_avalon_2017_pt.dbc new file mode 100644 index 00000000000000..b867e937065b5f --- /dev/null +++ b/opendbc/generator/toyota/toyota_avalon_2017_pt.dbc @@ -0,0 +1,33 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|65535] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|3] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc new file mode 100644 index 00000000000000..c21dc779eb2ae4 --- /dev/null +++ b/opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc @@ -0,0 +1,36 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_chr_2018_pt.dbc b/opendbc/generator/toyota/toyota_chr_2018_pt.dbc new file mode 100644 index 00000000000000..60865fb46f552d --- /dev/null +++ b/opendbc/generator/toyota/toyota_chr_2018_pt.dbc @@ -0,0 +1,33 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc new file mode 100644 index 00000000000000..c86fcaaf659c86 --- /dev/null +++ b/opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc @@ -0,0 +1,36 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc b/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc new file mode 100644 index 00000000000000..caf7b6388d93cc --- /dev/null +++ b/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc @@ -0,0 +1,32 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1.0,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_highlander_2017_pt.dbc b/opendbc/generator/toyota/toyota_highlander_2017_pt.dbc new file mode 100644 index 00000000000000..b867e937065b5f --- /dev/null +++ b/opendbc/generator/toyota/toyota_highlander_2017_pt.dbc @@ -0,0 +1,33 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|65535] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|3] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_highlander_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_highlander_hybrid_2018_pt.dbc new file mode 100644 index 00000000000000..8fe5ec1991f18a --- /dev/null +++ b/opendbc/generator/toyota/toyota_highlander_hybrid_2018_pt.dbc @@ -0,0 +1,33 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 5 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/opendbc/generator/toyota/toyota_prius_2017_pt.dbc b/opendbc/generator/toyota/toyota_prius_2017_pt.dbc new file mode 100644 index 00000000000000..d1a6d27db87ca1 --- /dev/null +++ b/opendbc/generator/toyota/toyota_prius_2017_pt.dbc @@ -0,0 +1,40 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1083 AUTOPARK_STATUS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 1083 STATE "when the dashboard button is pressed, the value changes from zero to non-zero"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc new file mode 100644 index 00000000000000..e9d748b6c258d6 --- /dev/null +++ b/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc @@ -0,0 +1,32 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc new file mode 100644 index 00000000000000..8fe5ec1991f18a --- /dev/null +++ b/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc @@ -0,0 +1,33 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 5 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/opendbc/gm_global_a_chassis.dbc b/opendbc/gm_global_a_chassis.dbc index 791a08a3e8185f..e1fc1ccbffe53e 100644 --- a/opendbc/gm_global_a_chassis.dbc +++ b/opendbc/gm_global_a_chassis.dbc @@ -1,75 +1,75 @@ -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_: K182_PACM K43_PSCM K17_EBCM NEO K124_ASCM - - - -BO_ 823 PACMParkAssitCmd: 7 NEO - SG_ RollingCounter : 35|2@0+ (1,0) [0|0] "" NEO - SG_ SteeringWheelChecksum : 47|16@0+ (1,0) [0|0] "" NEO - SG_ SteeringWheelCmd : 23|16@0+ (1,0) [0|0] "" NEO - -BO_ 560 EBCMRegen: 6 K17_EBCM - SG_ Regen : 1|10@0+ (1,0) [0|0] "" NEO - -BO_ 368 EBCMFrictionBrakeStatus: 8 K17_EBCM - SG_ FrictionBrakePressure : 23|16@0+ (1,0) [0|0] "" NEO - -BO_ 789 EBCMFrictionBrakeCmd: 5 K17_EBCM - SG_ RollingCounter : 33|2@0+ (1,0) [0|0] "" NEO - SG_ FrictionBrakeMode : 7|4@0+ (1,0) [0|0] "" NEO - SG_ FrictionBrakeChecksum : 23|16@0+ (1,0) [0|0] "" NEO - SG_ FirctionBrakeCmd : 3|12@0+ (1,0) [0|0] "" NEO - -BO_TX_BU_ 823 : K43_PSCM,NEO; -BO_TX_BU_ 789 : NEO,K17_EBCM; - - -CM_ BU_ K182_PACM "Parking Assist Control Module"; -CM_ BU_ K43_PSCM "Power Steering Control Module"; -CM_ BU_ K17_EBCM "Electronic Brake Control Module"; -CM_ BU_ NEO "Comma NEO"; -CM_ BU_ K124_ASCM "Active Safety Control Module"; -BA_DEF_ "UseGMParameterIDs" INT 0 0; -BA_DEF_ "ProtocolType" STRING ; -BA_DEF_ "BusType" STRING ; -BA_DEF_DEF_ "UseGMParameterIDs" 1; -BA_DEF_DEF_ "ProtocolType" "GMLAN"; -BA_DEF_DEF_ "BusType" ""; -BA_ "UseGMParameterIDs" 0; -BA_ "BusType" "CAN"; -BA_ "ProtocolType" "GMLAN"; - +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_: K182_PACM K43_PSCM K17_EBCM NEO K124_ASCM + + + +BO_ 823 PACMParkAssitCmd: 7 NEO + SG_ RollingCounter : 35|2@0+ (1,0) [0|0] "" NEO + SG_ SteeringWheelChecksum : 47|16@0+ (1,0) [0|0] "" NEO + SG_ SteeringWheelCmd : 23|16@0+ (1,0) [0|0] "" NEO + +BO_ 560 EBCMRegen: 6 K17_EBCM + SG_ Regen : 1|10@0+ (1,0) [0|0] "" NEO + +BO_ 368 EBCMFrictionBrakeStatus: 8 K17_EBCM + SG_ FrictionBrakePressure : 23|16@0+ (1,0) [0|0] "" NEO + +BO_ 789 EBCMFrictionBrakeCmd: 5 K17_EBCM + SG_ RollingCounter : 33|2@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeMode : 7|4@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeChecksum : 23|16@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeCmd : 3|12@0- (1,0) [0|0] "" NEO + +BO_TX_BU_ 823 : K43_PSCM,NEO; +BO_TX_BU_ 789 : NEO,K17_EBCM; + + +CM_ BU_ K182_PACM "Parking Assist Control Module"; +CM_ BU_ K43_PSCM "Power Steering Control Module"; +CM_ BU_ K17_EBCM "Electronic Brake Control Module"; +CM_ BU_ NEO "Comma NEO"; +CM_ BU_ K124_ASCM "Active Safety Control Module"; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "UseGMParameterIDs" 0; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; + diff --git a/opendbc/gm_global_a_lowspeed.dbc b/opendbc/gm_global_a_lowspeed.dbc index 9fc4f86e23ae37..9ea4d1da3d93db 100644 --- a/opendbc/gm_global_a_lowspeed.dbc +++ b/opendbc/gm_global_a_lowspeed.dbc @@ -1,110 +1,110 @@ -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_: GMLAN NEO -VAL_TABLE_ GearShifter 3 "Park" 0 "Drive/Low" ; -VAL_TABLE_ DriverDoorStatus 1 "Opened" 0 "Closed" ; -VAL_TABLE_ LKAGapButton 2 "???" 1 "??" 0 "None" ; -VAL_TABLE_ CruiseButtons 12 "Cancel" 10 "Enabled" 6 "Set" 4 "Resume" 2 "None" ; -VAL_TABLE_ CruiseControlActive 1 "Active" 0 "Inactive" ; -VAL_TABLE_ BlinkerStatus 1 "Active" 0 "Inactive" ; - - -BO_ 274923520 DriverDoorStatus: 1 GMLAN - SG_ DriverDoorOpened : 0|1@0+ (1,0) [0|0] "" NEO - -BO_ 272629760 Chime: 5 NEO - SG_ ChimeType : 7|8@0+ (1,0) [0|0] "" GMLAN - SG_ ChimeRepeat : 23|8@0+ (1,0) [0|0] "" GMLAN - SG_ ChimeDuration : 15|8@0+ (1,0) [0|0] "" GMLAN - SG_ ChimeByte5 : 39|8@0+ (1,0) [0|0] "" GMLAN - SG_ ChimeByte4 : 31|8@0+ (1,0) [0|0] "" GMLAN - -BO_ 270581760 BlinkerStatus: 5 GMLAN - SG_ RightBlinker : 6|1@0+ (1,0) [0|0] "" NEO - SG_ LeftBlinker : 7|1@0+ (1,0) [0|0] "" NEO - SG_ BlinkerLight : 25|1@0+ (1,0) [0|0] "" NEO - -BO_ 270794752 SteeringWheelAngle: 8 GMLAN - SG_ SteeringWheelAngle : 39|16@0- (0.0625,0) [-540|540] "deg" NEO - -BO_ 271368192 GearShifter: 8 GMLAN - SG_ GearShifter : 17|2@0+ (1,0) [0|3] "" NEO - -BO_ 271360000 GasPedalRegenCruise: 8 GMLAN - SG_ CruiseControlActive : 56|1@0+ (1,0) [0|0] "" GMLAN - SG_ MaxRegen : 12|1@0+ (1,0) [0|1] "" GMLAN,NEO - SG_ GasPedal : 47|8@0+ (1,0) [0|254] "" GMLAN,NEO - SG_ GearShifter2NotUsed : 55|8@0+ (1,0) [0|255] "" GMLAN,NEO - -BO_ 270860288 BrakePedal: 2 GMLAN - SG_ BrakeLevel : 2|2@0+ (1,0) [0|3] "" NEO - SG_ BrakeSensor : 15|8@0+ (1,0) [0|255] "" NEO - -BO_ 275480576 WheelSpeed: 8 GMLAN - SG_ WheelSpeedFL : 7|16@0+ (0.01,0) [0|70] "yd/s" NEO - SG_ WheelSpeedFR : 39|16@0+ (0.01,0) [0|70] "yd/s" NEO - SG_ WheelSpeedRL : 23|16@0+ (0.01,0) [0|70] "yd/s" NEO - SG_ WheelSpeedRR : 55|16@0+ (0.01,0) [0|70] "yd/s" NEO - -BO_ 270598144 VehicleSpeed: 8 GMLAN - SG_ VehicleSpeed1 : 7|16@0+ (0.01,0) [0|100] "mph" NEO - SG_ VehicleSpeed2 : 39|16@0+ (0.01,0) [0|100] "mph" NEO - -BO_ 276135936 CruiseButtons: 3 GMLAN - SG_ CruiseButtons : 3|4@0+ (1,0) [0|12] "" NEO - -BO_ 276127744 CruiseButtons2: 1 GMLAN - SG_ LKAGapButton : 1|2@0+ (1,0) [0|2] "" NEO - - - -BA_DEF_ "UseGMParameterIDs" INT 0 0; -BA_DEF_ "ProtocolType" STRING ; -BA_DEF_ "BusType" STRING ; -BA_DEF_DEF_ "UseGMParameterIDs" 1; -BA_DEF_DEF_ "ProtocolType" "GMLAN"; -BA_DEF_DEF_ "BusType" ""; -BA_ "BusType" "CAN"; -BA_ "ProtocolType" "GMLAN"; -VAL_ 274923520 DriverDoorOpened 1 "Opened" 0 "Closed" ; -VAL_ 270581760 RightBlinker 1 "Active" 0 "Inactive" ; -VAL_ 270581760 LeftBlinker 1 "Active" 0 "Inactive" ; -VAL_ 270581760 BlinkerLight 1 "Active" 0 "Inactive" ; -VAL_ 271368192 GearShifter 3 "Park" 0 "Drive/Low" ; -VAL_ 271360000 CruiseControlActive 1 "Active" 0 "Inactive" ; -VAL_ 276135936 CruiseButtons 12 "Cancel" 10 "Enabled" 6 "Set" 4 "Resume" 2 "None" ; -VAL_ 276127744 LKAGapButton 2 "???" 1 "??" 0 "None" ; - +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_: GMLAN NEO +VAL_TABLE_ GearShifter 3 "Park" 0 "Drive/Low" ; +VAL_TABLE_ DriverDoorStatus 1 "Opened" 0 "Closed" ; +VAL_TABLE_ LKAGapButton 2 "???" 1 "??" 0 "None" ; +VAL_TABLE_ CruiseButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_TABLE_ CruiseControlActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ BlinkerStatus 1 "Active" 0 "Inactive" ; + + +BO_ 274923520 DriverDoorStatus: 1 GMLAN + SG_ DriverDoorOpened : 0|1@0+ (1,0) [0|0] "" NEO + +BO_ 272629760 Chime: 5 NEO + SG_ ChimeType : 7|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeRepeat : 23|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeDuration : 15|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeByte5 : 39|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeByte4 : 31|8@0+ (1,0) [0|0] "" GMLAN + +BO_ 270581760 BlinkerStatus: 5 GMLAN + SG_ RightBlinker : 6|1@0+ (1,0) [0|0] "" NEO + SG_ LeftBlinker : 7|1@0+ (1,0) [0|0] "" NEO + SG_ BlinkerLight : 25|1@0+ (1,0) [0|0] "" NEO + +BO_ 270794752 SteeringWheelAngle: 8 GMLAN + SG_ SteeringWheelAngle : 39|16@0- (0.0625,0) [-540|540] "deg" NEO + +BO_ 271368192 GearShifter: 8 GMLAN + SG_ GearShifter : 17|2@0+ (1,0) [0|3] "" NEO + +BO_ 271360000 GasPedalRegenCruise: 8 GMLAN + SG_ CruiseControlActive : 56|1@0+ (1,0) [0|0] "" GMLAN + SG_ MaxRegen : 12|1@0+ (1,0) [0|1] "" GMLAN,NEO + SG_ GasPedal : 47|8@0+ (1,0) [0|254] "" GMLAN,NEO + SG_ GearShifter2NotUsed : 55|8@0+ (1,0) [0|255] "" GMLAN,NEO + +BO_ 270860288 BrakePedal: 2 GMLAN + SG_ BrakeLevel : 2|2@0+ (1,0) [0|3] "" NEO + SG_ BrakeSensor : 15|8@0+ (1,0) [0|255] "" NEO + +BO_ 275480576 WheelSpeed: 8 GMLAN + SG_ WheelSpeedFL : 7|16@0+ (0.01,0) [0|70] "yd/s" NEO + SG_ WheelSpeedFR : 39|16@0+ (0.01,0) [0|70] "yd/s" NEO + SG_ WheelSpeedRL : 23|16@0+ (0.01,0) [0|70] "yd/s" NEO + SG_ WheelSpeedRR : 55|16@0+ (0.01,0) [0|70] "yd/s" NEO + +BO_ 270598144 VehicleSpeed: 8 GMLAN + SG_ VehicleSpeed1 : 7|16@0+ (0.01,0) [0|100] "mph" NEO + SG_ VehicleSpeed2 : 39|16@0+ (0.01,0) [0|100] "mph" NEO + +BO_ 276135936 CruiseButtons: 3 GMLAN + SG_ CruiseButtons : 3|3@0+ (1,0) [0|12] "" NEO + +BO_ 276127744 CruiseButtons2: 1 GMLAN + SG_ LKAGapButton : 1|2@0+ (1,0) [0|2] "" NEO + + + +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; +VAL_ 274923520 DriverDoorOpened 1 "Opened" 0 "Closed" ; +VAL_ 270581760 RightBlinker 1 "Active" 0 "Inactive" ; +VAL_ 270581760 LeftBlinker 1 "Active" 0 "Inactive" ; +VAL_ 270581760 BlinkerLight 1 "Active" 0 "Inactive" ; +VAL_ 271368192 GearShifter 3 "Park" 0 "Drive/Low" ; +VAL_ 271360000 CruiseControlActive 1 "Active" 0 "Inactive" ; +VAL_ 276135936 CruiseButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_ 276127744 LKAGapButton 2 "???" 1 "??" 0 "None" ; + diff --git a/opendbc/gm_global_a_object.dbc b/opendbc/gm_global_a_object.dbc index c1a50ad94d7d05..8847bab39df0d1 100644 --- a/opendbc/gm_global_a_object.dbc +++ b/opendbc/gm_global_a_object.dbc @@ -1,255 +1,284 @@ -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_: K109_FCM B233B_LRR NEO K124_ASCM -VAL_TABLE_ RangeMode 1 "Active" 0 "Inactive" ; -VAL_TABLE_ TrkConf 3 "Confident" 2 "Speculative" 1 "Highly speculative" 0 "Invalid" ; -VAL_TABLE_ TrkMeasStatus 3 "Measured current cycle" 2 "Latent track not detected " 1 "New object" 0 "No object" ; -VAL_TABLE_ TrkDynProp 4 "Moving in opposite direction" 3 "Moving in same direction " 2 "Has moved but currenty stopped" 1 "Has never moved," 0 "Unkown" ; - - -BO_ 3221225472 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX - SG_ Always12 : 0|8@0+ (1,0) [0|0] "" Vector__XXX - SG_ TimeStatusChecksum : 0|12@0+ (1,0) [0|0] "" Vector__XXX - -BO_ 161 ASCMTimeStatus: 7 NEO - SG_ TimeStatus : 7|28@0+ (1,0) [0|0] "" B233B_LRR - SG_ RollingCounter : 27|2@0+ (1,0) [0|0] "" B233B_LRR - -BO_ 774 ASCMSteeringStatus: 8 NEO - SG_ ASCMSterringStatusChecksum : 55|16@0+ (1,0) [0|0] "" B233B_LRR - SG_ AlwaysF0 : 15|8@0+ (1,0) [0|0] "" B233B_LRR - SG_ Always20 : 23|8@0+ (1,0) [0|0] "" B233B_LRR - SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" B233B_LRR - -BO_ 784 ASCMHeadlight: 2 NEO - SG_ Always42 : 7|8@0+ (1,0) [0|0] "" B233B_LRR - SG_ Always4 : 15|8@0+ (1,0) [0|0] "" B233B_LRR - -BO_ 776 ASCMAccSpeedStatus: 7 NEO - SG_ AccSpeedChecksum : 42|11@0+ (1,0) [0|0] "" B233B_LRR - SG_ RollingCounter : 46|2@0+ (1,0) [0|0] "" B233B_LRR - SG_ NearRangeMode : 43|1@0+ (1,0) [0|0] "" B233B_LRR - SG_ FarRangeMode : 44|1@0+ (1,0) [0|0] "" B233B_LRR - SG_ VehicleAcceleration : 19|12@0+ (1,0) [0|0] "" B233B_LRR - SG_ VehicleSpeed : 15|12@0+ (1,0) [0|0] "" B233B_LRR - SG_ AlwaysOne : 3|1@0+ (1,0) [0|0] "" B233B_LRR - -BO_ 1120 LRRNumObjects: 8 B233B_LRR - SG_ LRRNumObjects : 20|5@0+ (1,0) [0|0] "" NEO - -BO_ 1134 LRRObject14: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1132 LRRObject12: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1131 LRRObject11: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1130 LRRObject10: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1129 LRRObject09: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1128 LRRObject08: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1127 LRRObject07: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1126 LRRObject06: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1125 LRRObject05: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1124 LRRObject04: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1123 LRRObject03: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1140 LRRObject20: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1139 LRRObject19: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1138 LRRObject18: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1137 LRRObject17: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1136 LRRObject16: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1135 LRRObject15: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1133 LRRObject13: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1122 LRRObject02: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_ 1121 LRRObject01: 8 B233B_LRR - SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO - SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO - SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO - SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO - SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO - SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO - -BO_TX_BU_ 161 : K124_ASCM,NEO; -BO_TX_BU_ 774 : K124_ASCM,NEO; -BO_TX_BU_ 784 : K124_ASCM,NEO; -BO_TX_BU_ 776 : K124_ASCM,NEO; - - -CM_ BU_ K109_FCM "Frontview Camera Module "; -CM_ BU_ B233B_LRR "Radar Sensor Module Long Range"; -CM_ BU_ NEO "Comma NEO"; -CM_ BU_ K124_ASCM "Active Safety Control Module"; -CM_ BO_ 3221225472 "This is a message for not used signals, created by Vector CANdb++ DBC OLE DB Provider."; -BA_DEF_ "UseGMParameterIDs" INT 0 0; -BA_DEF_ "ProtocolType" STRING ; -BA_DEF_ "BusType" STRING ; -BA_DEF_DEF_ "UseGMParameterIDs" 1; -BA_DEF_DEF_ "ProtocolType" "GMLAN"; -BA_DEF_DEF_ "BusType" ""; -BA_ "BusType" "CAN"; -BA_ "ProtocolType" "GMLAN"; -BA_ "UseGMParameterIDs" 0; -VAL_ 776 NearRangeMode 1 "Active" 0 "Inactive" ; -VAL_ 776 FarRangeMode 1 "Active" 0 "Inactive" ; - +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_: K109_FCM B233B_LRR NEO K124_ASCM +VAL_TABLE_ RangeMode 1 "Active" 0 "Inactive" ; +VAL_TABLE_ TrkConf 3 "Confident" 2 "Speculative" 1 "Highly speculative" 0 "Invalid" ; +VAL_TABLE_ TrkMeasStatus 3 "Measured current cycle" 2 "Latent track not detected " 1 "New object" 0 "No object" ; +VAL_TABLE_ TrkDynProp 4 "Moving in opposite direction" 3 "Moving in same direction " 2 "Has moved but currenty stopped" 1 "Has never moved," 0 "Unkown" ; + + +BO_ 3221225472 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX + SG_ Always12 : 0|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TimeStatusChecksum : 0|12@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 161 ASCMTimeStatus: 7 NEO + SG_ TimeStatus : 7|28@0+ (1,0) [0|0] "" B233B_LRR + SG_ RollingCounter : 27|2@0+ (1,0) [0|0] "" B233B_LRR + +BO_ 774 ASCMSteeringStatus: 8 NEO + SG_ ASCMSterringStatusChecksum : 55|16@0+ (1,0) [0|0] "" B233B_LRR + SG_ AlwaysF0 : 15|8@0+ (1,0) [0|0] "" B233B_LRR + SG_ Always20 : 23|8@0+ (1,0) [0|0] "" B233B_LRR + SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" B233B_LRR + +BO_ 784 ASCMHeadlight: 2 NEO + SG_ Always42 : 7|8@0+ (1,0) [0|0] "" B233B_LRR + SG_ Always4 : 15|8@0+ (1,0) [0|0] "" B233B_LRR + +BO_ 776 ASCMAccSpeedStatus: 7 NEO + SG_ AccSpeedChecksum : 42|11@0+ (1,0) [0|0] "" B233B_LRR + SG_ RollingCounter : 46|2@0+ (1,0) [0|0] "" B233B_LRR + SG_ NearRangeMode : 43|1@0+ (1,0) [0|0] "" B233B_LRR + SG_ FarRangeMode : 44|1@0+ (1,0) [0|0] "" B233B_LRR + SG_ VehicleAcceleration : 19|12@0+ (1,0) [0|0] "" B233B_LRR + SG_ VehicleSpeed : 15|12@0+ (1,0) [0|0] "" B233B_LRR + SG_ AlwaysOne : 3|1@0+ (1,0) [0|0] "" B233B_LRR + +BO_ 1120 F_LRR_Obj_Header: 8 LRR_FO + SG_ FLRRRollingCount : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRModeCmdFdbk : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRNumValidTargets : 20|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ FLRRTimeStampV : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTimeStamp : 2|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ FLRRRoadTypeInfo : 5|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ FLRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRLonVelPlsblityFlt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRYawRtPlsblityFlt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTunlDtctd : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1134 LRRObject14: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1132 LRRObject12: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1131 LRRObject11: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1130 LRRObject10: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1129 LRRObject09: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1128 LRRObject08: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1127 LRRObject07: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1126 LRRObject06: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1125 LRRObject05: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1124 LRRObject04: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1123 LRRObject03: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1140 LRRObject20: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1139 LRRObject19: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1138 LRRObject18: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1137 LRRObject17: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1136 LRRObject16: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1135 LRRObject15: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1133 LRRObject13: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1122 LRRObject02: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_ 1121 LRRObject01: 8 B233B_LRR + SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO + SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO + SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO + SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO + SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO + SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO + +BO_TX_BU_ 161 : K124_ASCM,NEO; +BO_TX_BU_ 774 : K124_ASCM,NEO; +BO_TX_BU_ 784 : K124_ASCM,NEO; +BO_TX_BU_ 776 : K124_ASCM,NEO; + + +CM_ BU_ K109_FCM "Frontview Camera Module "; +CM_ BU_ B233B_LRR "Radar Sensor Module Long Range"; +CM_ BU_ NEO "Comma NEO"; +CM_ BU_ K124_ASCM "Active Safety Control Module"; +CM_ BO_ 3221225472 "This is a message for not used signals, created by Vector CANdb++ DBC OLE DB Provider."; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; +BA_ "UseGMParameterIDs" 0; +VAL_ 776 NearRangeMode 1 "Active" 0 "Inactive" ; +VAL_ 776 FarRangeMode 1 "Active" 0 "Inactive" ; + diff --git a/opendbc/gm_global_a_powertrain.dbc b/opendbc/gm_global_a_powertrain.dbc index f87019560a1774..27f181dc0fa681 100644 --- a/opendbc/gm_global_a_powertrain.dbc +++ b/opendbc/gm_global_a_powertrain.dbc @@ -1,216 +1,255 @@ -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_: K16_BECM K73_TCIC K9_BCM K43_PSCM K17_EBCM K20_ECM K114B_HPCM NEO K124_ASCM -VAL_TABLE_ TurnSignals 2 "Right Turn" 1 "Left Turn" 0 "None" ; -VAL_TABLE_ ACCLeadCar 1 "Present" 0 "Not Present" ; -VAL_TABLE_ ACCCmdActive 1 "Active" 0 "Inactive" ; -VAL_TABLE_ BrakePedalPressed 1 "Pressed" 0 "Depressed" ; -VAL_TABLE_ ACCGapButton 1 "Active" 0 "Inactive" ; -VAL_TABLE_ LKAButton 1 "Active" 0 "Inactive" ; -VAL_TABLE_ ACCCancelButton 1 "Active" 0 "Inactive" ; -VAL_TABLE_ PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; -VAL_TABLE_ DriverDoorStatus 1 "Opened" 0 "Closed" ; -VAL_TABLE_ LKASteeringCmdActive 1 "Active" 0 "Inactive" ; -VAL_TABLE_ ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; -VAL_TABLE_ ACCButton 1 "Pressed" 0 "Depressed" ; -VAL_TABLE_ GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; -VAL_TABLE_ GasRegenCmdActive 1 "Active" 0 "Inactive" ; -VAL_TABLE_ LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; -VAL_TABLE_ HandsOffSWDetectionStatus 1 "Hands On" 0 "Hands Off" ; -VAL_TABLE_ HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; - - -BO_ 320 BCMTurnSignals: 3 K9_BCM - SG_ TurnSignals : 19|2@0+ (1,0) [0|0] "" NEO - -BO_ 1217 ECMEngineCoolantTemp: 8 K20_ECM - SG_ EngineCoolantTemp : 23|8@0+ (1,-40) [0|0] "°C" NEO - -BO_ 1249 VIN_Part2: 8 K20_ECM - SG_ VINPart2 : 7|64@0+ (1,0) [0|0] "" NEO - -BO_ 1300 VIN_Part1: 8 K20_ECM - SG_ VINPart1 : 7|64@0+ (1,0) [0|0] "" NEO - -BO_ 481 ASCMSteeringButton: 7 K124_ASCM - SG_ ACCGapButton : 22|1@0+ (1,0) [0|0] "" NEO - SG_ LKAButton : 23|1@0+ (1,0) [0|0] "" NEO - SG_ ACCCancelButton : 7|1@0+ (1,0) [0|0] "" NEO - -BO_ 1912 PSCM_778: 8 K43_PSCM - -BO_ 328 PSCM_148: 1 K43_PSCM - -BO_ 309 ECMPRDNL: 8 K20_ECM - SG_ PRNDL : 2|3@0+ (1,0) [0|0] "" NEO - -BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC - SG_ GPSLongitude : 39|32@0+ (1,0) [0|0] "milliarcsecond" NEO - SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO - -BO_ 1001 ECMVehicleSpeed: 8 K20_ECM - SG_ VehicleSpeed : 7|16@0+ (0.01,0) [0|0] "mph" NEO - -BO_ 298 BCMDoorStatus: 8 K9_BCM - SG_ DriverDoorStatus : 55|1@0+ (1,0) [0|0] "" NEO - -BO_ 381 MSG_17D: 6 K20_ECM - SG_ MSG17D_AccPower : 35|12@0- (1,0) [0|0] "" NEO - -BO_ 201 ECMEngineStatus: 8 K20_ECM - SG_ EngineTPS : 39|8@0+ (0.392156863,0) [0|100.000000065] "%" NEO - SG_ EngineRPM : 15|16@0+ (0.25,0) [0|0] "RPM" NEO - -BO_ 209 EBCMBrakePedalTorque: 7 K17_EBCM - SG_ BrakePedalTorque : 3|12@0+ (1,0) [0|0] "" NEO - -BO_ 384 ASCMLKASteeringCmd: 4 NEO - SG_ RollingCounter : 5|2@0+ (1,0) [0|0] "" NEO - SG_ LKASteeringCmdChecksum : 19|12@0+ (1,0) [0|0] "" NEO - SG_ LKASteeringCmdActive : 3|1@0+ (1,0) [0|0] "" NEO - SG_ LKASteeringCmd : 2|11@0+ (1,0) [0|0] "" NEO - -BO_ 880 ASCMActiveCruiseControlStatus: 6 K124_ASCM - SG_ ACCLeadCar : 44|1@0+ (1,0) [0|0] "" Vector__XXX - SG_ ACCAlwaysOne2 : 32|1@0+ (1,0) [0|0] "" Vector__XXX - SG_ ACCAlwaysOne : 0|1@0+ (1,0) [0|0] "" Vector__XXX - SG_ ACCSpeedSetpoint : 19|12@0+ (1,0) [0|0] "km/h" NEO - SG_ ACCGapLevel : 21|2@0+ (1,0) [0|0] "" NEO - SG_ ACCResumeButton : 1|1@0+ (1,0) [0|0] "" NEO - SG_ ACCCmdActive : 23|1@0+ (1,0) [0|0] "" NEO - -BO_ 1930 ASCM_78A: 7 K124_ASCM - -BO_ 1296 ASCM_510: 4 K124_ASCM - -BO_ 1034 ASCM_40A: 7 K124_ASCM - -BO_ 869 ASCM_365: 4 K124_ASCM - -BO_ 717 ASCM_2CD: 5 K124_ASCM - -BO_ 1033 ASCMKeepAlive: 7 NEO - SG_ ASCMKeepAliveAllZero : 7|56@0+ (1,0) [0|0] "" NEO - -BO_ 485 PSCMSteeringAngle: 8 K43_PSCM - SG_ SteeringWheelAngle : 15|16@0- (0.0625,0) [-540|540] "deg" NEO - SG_ SteeringWheelRate : 27|12@0- (0.5,0) [-100|100] "deg/s" NEO - -BO_ 388 PSCMStatus: 8 K43_PSCM - SG_ HandsOffSWDetectionMode : 20|2@0+ (1,0) [0|3] "" NEO - SG_ HandsOffSWlDetectionStatus : 21|1@0+ (1,0) [0|1] "" NEO - SG_ LKATorqueDeliveredStatus : 5|3@0+ (1,0) [0|7] "" NEO - SG_ LKADriverAppldTrq : 50|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO - SG_ LKATotalTorqueDelivered : 2|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO - -BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM - SG_ YawRate : 51|12@0- (0.0625,0) [-2047|2047] "grad/s" NEO - SG_ LateralAcceleration : 3|12@0- (0.0161,0) [-2047|2047] "m/s2" NEO - SG_ BrakePedalPressed : 6|1@0+ (1,0) [0|0] "" NEO - -BO_ 189 EBCMRegenPaddle: 7 K17_EBCM - SG_ RegenPaddle : 7|4@0+ (1,0) [0|0] "" NEO - -BO_ 190 ECMAcceleratorPos: 6 K20_ECM - SG_ AcceleratorPos : 23|8@0+ (1,0) [0|0] "" NEO - -BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM - SG_ GasRegenAlwaysOne2 : 9|1@0+ (1,1) [1|1] "" NEO - SG_ GasRegenAlwaysOne : 14|1@0+ (1,1) [1|1] "" NEO - SG_ GasRegenChecksum : 47|24@0+ (1,0) [0|0] "" NEO - SG_ GasRegenCmdActiveInv : 32|1@0+ (1,0) [0|0] "" NEO - SG_ GasRegenFullStopActive : 13|1@0+ (1,0) [0|0] "" NEO - SG_ GasRegenCmdActive : 0|1@0+ (1,0) [0|0] "" NEO - SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" NEO - SG_ GasRegenCmd : 23|16@0+ (1,0) [0|0] "" NEO - -BO_ 840 EBCMWheelSpdFront: 4 K17_EBCM - SG_ FLWheelSpd : 7|16@0+ (0.0305,0) [0|255] "km/h" NEO - SG_ FRWheelSpd : 23|16@0+ (0.0305,0) [0|255] "km/h" NEO - -BO_ 842 EBCMWheelSpdRear: 4 K17_EBCM - SG_ RLWheelSpd : 7|16@0+ (0.0305,0) [0|255] "km/h" NEO - SG_ RRWheelSpd : 23|16@0+ (0.0305,0) [0|255] "km/h" NEO - -BO_ 241 EBCMBrakePedalPosition: 6 K17_EBCM - SG_ BrakePedalPosition : 15|8@0+ (0.392157,0) [0|255] "%" NEO - -BO_ 711 BECMBatteryVoltageCurrent: 6 K17_EBCM - SG_ HVBatteryVoltage : 31|12@0+ (0.125,0) [0|511.875] "V" NEO - SG_ HVBatteryCurrent : 12|13@0- (0.15,0) [-614.4|614.25] "A" NEO - -BO_TX_BU_ 384 : K124_ASCM,NEO; -BO_TX_BU_ 880 : NEO,K124_ASCM; -BO_TX_BU_ 1033 : K124_ASCM,NEO; -BO_TX_BU_ 715 : NEO,K124_ASCM; - - -CM_ BU_ K16_BECM "Battery Energy Control Module"; -CM_ BU_ K73_TCIC "Telematics Communication Control Module"; -CM_ BU_ K9_BCM "Body Control Module"; -CM_ BU_ K43_PSCM "Power Steering Control Module"; -CM_ BU_ K17_EBCM "Electronic Brake Control Module"; -CM_ BU_ K20_ECM "Engine Control Module"; -CM_ BU_ K114B_HPCM "Hybrid Powertrain Control Module"; -CM_ BU_ NEO "Comma NEO"; -CM_ BU_ K124_ASCM "Active Safety Control Module"; -CM_ SG_ 381 MSG17D_AccPower "Need to investigate"; -BA_DEF_ "UseGMParameterIDs" INT 0 0; -BA_DEF_ "ProtocolType" STRING ; -BA_DEF_ "BusType" STRING ; -BA_DEF_DEF_ "UseGMParameterIDs" 1; -BA_DEF_DEF_ "ProtocolType" "GMLAN"; -BA_DEF_DEF_ "BusType" ""; -BA_ "BusType" "CAN"; -BA_ "ProtocolType" "GMLAN"; -BA_ "UseGMParameterIDs" 0; -VAL_ 481 ACCGapButton 1 "Active" 0 "Inactive" ; -VAL_ 481 LKAButton 1 "Active" 0 "Inactive" ; -VAL_ 481 ACCCancelButton 1 "Active" 0 "Inactive" ; -VAL_ 309 PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; -VAL_ 298 DriverDoorStatus 1 "Opened" 0 "Closed" ; -VAL_ 384 LKASteeringCmdActive 1 "Active" 0 "Inactive" ; -VAL_ 880 ACCLeadCar 1 "Present" 0 "Not Present" ; -VAL_ 880 ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; -VAL_ 880 ACCResumeButton 1 "Pressed" 0 "Depressed" ; -VAL_ 880 ACCCmdActive 1 "Active" 0 "Inactive" ; -VAL_ 388 HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; -VAL_ 388 HandsOffSWlDetectionStatus 1 "Hands On" 0 "Hands Off" ; -VAL_ 388 LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; -VAL_ 489 BrakePedalPressed 1 "Pressed" 0 "Depressed" ; -VAL_ 715 GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; -VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ; - +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_: K16_BECM K73_TCIC K9_BCM K43_PSCM K17_EBCM K20_ECM K114B_HPCM NEO K124_ASCM EPB +VAL_TABLE_ TurnSignals 2 "Right Turn" 1 "Left Turn" 0 "None" ; +VAL_TABLE_ Intellibeam 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HighBeamsActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HighBeamsTemporary 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCLeadCar 1 "Present" 0 "Not Present" ; +VAL_TABLE_ ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_TABLE_ DistanceButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKAButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_TABLE_ DriveModeButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; +VAL_TABLE_ ESPButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ DoorStatus 1 "Opened" 0 "Closed" ; +VAL_TABLE_ SeatBeltStatus 1 "Latched" 0 "Unlatched" ; +VAL_TABLE_ LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; +VAL_TABLE_ GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_TABLE_ GasRegenCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HandsOffSWDetectionStatus 1 "Hands On" 0 "Hands Off" ; +VAL_TABLE_ HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; + + +BO_ 189 EBCMRegenPaddle: 7 K17_EBCM + SG_ RegenPaddle : 7|4@0+ (1,0) [0|0] "" NEO + +BO_ 190 ECMAcceleratorPos: 6 K20_ECM + SG_ BrakePedalPos : 15|8@0+ (1,0) [0|0] "sticky" NEO + SG_ GasPedalAndAcc : 23|8@0+ (1,0) [0|0] "" NEO + +BO_ 201 ECMEngineStatus: 8 K20_ECM + SG_ EngineTPS : 39|8@0+ (0.392156863,0) [0|100.000000065] "%" NEO + SG_ EngineRPM : 15|16@0+ (0.25,0) [0|0] "RPM" NEO + SG_ CruiseMainOn : 29|1@0+ (1,0) [0|1] "" NEO + +BO_ 209 EBCMBrakePedalTorque: 7 K17_EBCM + SG_ BrakePedalTorque : 3|12@0+ (1,0) [0|0] "" NEO + +BO_ 241 EBCMBrakePedalPosition: 6 K17_EBCM + SG_ BrakePedalPosition : 15|8@0+ (1,0) [0|255] "" NEO + +BO_ 298 BCMDoorBeltStatus: 8 K9_BCM + SG_ RearLeftDoor : 8|1@0+ (1,0) [0|0] "" NEO + SG_ FrontLeftDoor : 9|1@0+ (1,0) [0|0] "" NEO + SG_ FrontRightDoor : 10|1@0+ (1,0) [0|0] "" NEO + SG_ RearRightDoor : 23|1@0+ (1,0) [0|0] "" NEO + SG_ LeftSeatBelt : 12|1@0+ (1,0) [0|0] "" NEO + SG_ RightSeatBelt : 53|1@0+ (1,0) [0|0] "" NEO + +BO_ 309 ECMPRDNL: 8 K20_ECM + SG_ PRNDL : 2|3@0+ (1,0) [0|0] "" NEO + SG_ ESPButton : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 320 BCMTurnSignals: 3 K9_BCM + SG_ TurnSignals : 19|2@0+ (1,0) [0|0] "" NEO + SG_ Intellibeam : 13|1@0+ (1,0) [0|1] "" XXX + SG_ HighBeamsActive : 7|1@0+ (1,0) [0|1] "" XXX + SG_ HighBeamsTemporary : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 328 PSCM_148: 1 K43_PSCM + +BO_ 381 ESPStatus: 6 K20_ECM + SG_ TractionControlOn : 5|1@0+ (1,0) [0|0] "" NEO + SG_ MSG17D_AccPower : 35|12@0- (1,0) [0|0] "" NEO + +BO_ 384 ASCMLKASteeringCmd: 4 NEO + SG_ RollingCounter : 5|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 19|12@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdActive : 3|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 2|11@0- (1,0) [0|0] "" NEO + +BO_ 388 PSCMStatus: 8 K43_PSCM + SG_ HandsOffSWDetectionMode : 20|2@0+ (1,0) [0|3] "" NEO + SG_ HandsOffSWlDetectionStatus : 21|1@0+ (1,0) [0|1] "" NEO + SG_ LKATorqueDeliveredStatus : 5|3@0+ (1,0) [0|7] "" NEO + SG_ LKADriverAppldTrq : 50|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO + SG_ LKATotalTorqueDelivered : 2|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO + +BO_ 417 AcceleratorPedal: 8 XXX + SG_ AcceleratorPedal : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 451 GasAndAcc: 8 XXX + SG_ GasPedalAndAcc2 : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 452 AcceleratorPedal2: 8 XXX + SG_ CruiseState : 15|3@0+ (1,0) [0|7] "" NEO + SG_ AcceleratorPedal2 : 47|8@0+ (1,0) [0|0] "" NEO + +BO_ 481 ASCMSteeringButton: 7 K124_ASCM + SG_ DistanceButton : 22|1@0+ (1,0) [0|0] "" NEO + SG_ LKAButton : 23|1@0+ (1,0) [0|0] "" NEO + SG_ ACCButtons : 46|3@0+ (1,0) [0|0] "" NEO + SG_ DriveModeButton : 39|1@0+ (1,0) [0|1] "" XXX + +BO_ 485 PSCMSteeringAngle: 8 K43_PSCM + SG_ SteeringWheelAngle : 15|16@0- (0.0625,0) [-540|540] "deg" NEO + SG_ SteeringWheelRate : 27|12@0- (0.5,0) [-100|100] "deg/s" NEO + +BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM + SG_ YawRate : 51|12@0- (0.0625,0) [-2047|2047] "grad/s" NEO + SG_ LateralAcceleration : 3|12@0- (0.0161,0) [-2047|2047] "m/s2" NEO + SG_ BrakePedalPressed : 6|1@0+ (1,0) [0|0] "" NEO + +BO_ 560 EPBStatus: 8 EPB + SG_ EPBClosed : 12|1@0+ (1,0) [0|1] "" NEO + +BO_ 711 BECMBatteryVoltageCurrent: 6 K17_EBCM + SG_ HVBatteryVoltage : 31|12@0+ (0.125,0) [0|511.875] "V" NEO + SG_ HVBatteryCurrent : 12|13@0- (0.15,0) [-614.4|614.25] "A" NEO + +BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM + SG_ GasRegenAlwaysOne2 : 9|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenAlwaysOne : 14|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenChecksum : 47|24@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActiveInv : 32|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenFullStopActive : 13|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActive : 0|1@0+ (1,0) [0|0] "" NEO + SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" NEO + SG_ GasRegenAlwaysOne3 : 23|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenCmd : 22|12@0+ (1,0) [0|0] "" NEO + +BO_ 717 ASCM_2CD: 5 K124_ASCM + +BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC + SG_ GPSLongitude : 39|32@0+ (1,0) [0|0] "milliarcsecond" NEO + SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO + +BO_ 840 EBCMWheelSpdFront: 4 K17_EBCM + SG_ FLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO + SG_ FRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO + +BO_ 842 EBCMWheelSpdRear: 4 K17_EBCM + SG_ RLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO + SG_ RRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO + +BO_ 869 ASCM_365: 4 K124_ASCM + +BO_ 880 ASCMActiveCruiseControlStatus: 6 K124_ASCM + SG_ ACCLeadCar : 44|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne2 : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCSpeedSetpoint : 19|12@0+ (1,0) [0|0] "km/h" NEO + SG_ ACCGapLevel : 21|2@0+ (1,0) [0|0] "" NEO + SG_ ACCResumeButton : 1|1@0+ (1,0) [0|0] "" NEO + SG_ ACCCmdActive : 23|1@0+ (1,0) [0|0] "" NEO + +BO_ 1001 ECMVehicleSpeed: 8 K20_ECM + SG_ VehicleSpeed : 7|16@0+ (0.01,0) [0|0] "mph" NEO + +BO_ 1033 ASCMKeepAlive: 7 NEO + SG_ ASCMKeepAliveAllZero : 7|56@0+ (1,0) [0|0] "" NEO + +BO_ 1034 ASCM_40A: 7 K124_ASCM + +BO_ 1217 ECMEngineCoolantTemp: 8 K20_ECM + SG_ EngineCoolantTemp : 23|8@0+ (1,-40) [0|0] "°C" NEO + +BO_ 1249 VIN_Part2: 8 K20_ECM + SG_ VINPart2 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1296 ASCM_510: 4 K124_ASCM + +BO_ 1300 VIN_Part1: 8 K20_ECM + SG_ VINPart1 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1912 PSCM_778: 8 K43_PSCM + +BO_ 1930 ASCM_78A: 7 K124_ASCM + +BO_TX_BU_ 384 : K124_ASCM,NEO; +BO_TX_BU_ 880 : NEO,K124_ASCM; +BO_TX_BU_ 1033 : K124_ASCM,NEO; +BO_TX_BU_ 715 : NEO,K124_ASCM; + + +CM_ BU_ K16_BECM "Battery Energy Control Module"; +CM_ BU_ K73_TCIC "Telematics Communication Control Module"; +CM_ BU_ K9_BCM "Body Control Module"; +CM_ BU_ K43_PSCM "Power Steering Control Module"; +CM_ BU_ K17_EBCM "Electronic Brake Control Module"; +CM_ BU_ K20_ECM "Engine Control Module"; +CM_ BU_ K114B_HPCM "Hybrid Powertrain Control Module"; +CM_ BU_ NEO "Comma NEO"; +CM_ BU_ K124_ASCM "Active Safety Control Module"; +CM_ SG_ 381 MSG17D_AccPower "Need to investigate"; +CM_ SG_ 190 GasPedalAndAcc "ACC baseline is 62"; +CM_ SG_ 451 GasPedalAndAcc2 "ACC baseline is 62"; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; +BA_ "UseGMParameterIDs" 0; +VAL_ 481 DistanceButton 1 "Active" 0 "Inactive" ; +VAL_ 481 LKAButton 1 "Active" 0 "Inactive" ; +VAL_ 481 ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_ 481 DriveModeButton 1 "Active" 0 "Inactive" ; +VAL_ 452 CruiseState 4 "Standstill" 3 "Faulted" 1 "Active" 0 "Off" ; +VAL_ 309 PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; +VAL_ 309 ESPButton 1 "Active" 0 "Inactive" ; +VAL_ 384 LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 880 ACCLeadCar 1 "Present" 0 "Not Present" ; +VAL_ 880 ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; +VAL_ 880 ACCResumeButton 1 "Pressed" 0 "Depressed" ; +VAL_ 880 ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 388 HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; +VAL_ 388 HandsOffSWlDetectionStatus 1 "Hands On" 0 "Hands Off" ; +VAL_ 388 LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; +VAL_ 489 BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_ 715 GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 320 Intellibeam 1 "Active" 0 "Inactive" ; +VAL_ 320 HighBeamsActive 1 "Active" 0 "Inactive" ; +VAL_ 320 HighBeamsTemporary 1 "Active" 0 "Inactive" ; + diff --git a/opendbc/honda_accord_lx15t_2018_can_generated.dbc b/opendbc/honda_accord_lx15t_2018_can_generated.dbc new file mode 100644 index 00000000000000..78896384986bdf --- /dev/null +++ b/opendbc/honda_accord_lx15t_2018_can_generated.dbc @@ -0,0 +1,320 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _bosch_2018.dbc starts here" +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_ + +BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 330 STEERING_SENSORS: 8 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_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX + SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM + SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + + BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 804 CRUISE: 8 PCM + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +CM_ "honda_accord_lx15t_2018_can.dbc starts here" + + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ BOH : 40|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_accord_s2t_2018_can_generated.dbc b/opendbc/honda_accord_s2t_2018_can_generated.dbc new file mode 100644 index 00000000000000..43a46aff831d0c --- /dev/null +++ b/opendbc/honda_accord_s2t_2018_can_generated.dbc @@ -0,0 +1,316 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _bosch_2018.dbc starts here" +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_ + +BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 330 STEERING_SENSORS: 8 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_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX + SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM + SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + + BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 804 CRUISE: 8 PCM + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +CM_ "honda_accord_s2t_2018_can.dbc starts here" + + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ BOH : 40|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_accord_touring_2016_can.dbc b/opendbc/honda_accord_touring_2016_can.dbc index 4339619a8a3778..d26ccd6a13a140 100644 --- a/opendbc/honda_accord_touring_2016_can.dbc +++ b/opendbc/honda_accord_touring_2016_can.dbc @@ -1,396 +1,396 @@ -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_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" NEO - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO - -BO_ 145 XXX_2: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ZEROS_BOH : 23|16@0+ (1,0) [0|15000] "" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 398 XXX_3: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX - -BO_ 401 GEARBOX: 8 PCM - SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO - SG_ GEAR : 35|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 426 XXX_4: 8 VSA - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 476 XXX_5: 4 XXX - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX - -BO_ 487 XXX_6: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM - SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM - SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM - SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM - -BO_ 507 XXX_7: 1 XXX - -BO_ 542 XXX_8: 7 XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX - -BO_ 545 XXX_9: 6 SCM - SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 56|4@1+ (1,0) [0|15] "" XXX - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 56|4@1+ (1,0) [0|15] "" XXX - -BO_ 661 XXX_10: 4 XXX - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX - -BO_ 662 CRUISE_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 777 XXX_11: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY - -BO_ 800 XXX_12: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 804 CRUISE: 8 PCM - SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO - SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 808 XXX_13: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 871 XXX_14: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 882 XXX_15: 2 XXX - SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX - -BO_ 884 XXX_16: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 891 XXX_17: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 918 XXX_18: 7 XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX - -BO_ 923 XXX_19: 2 XXX - SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX - -BO_ 927 ACC_HUD_2: 8 ADAS - SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY - SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY - SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY - SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY - SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY - SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 929 XXX_20: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 983 XXX_21: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 985 XXX_22: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX - -BO_ 1024 XXX_23: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1027 XXX_24: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 1036 XXX_25: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1039 XXX_26: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1057 XXX_27: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1064 XXX_28: 7 XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX - -BO_ 1088 XXX_29: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1089 XXX_30: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1108 XXX_31: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1125 XXX_32: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1296 XXX_33: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX - -BO_ 1365 XXX_34: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1424 XXX_35: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1600 XXX_36: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1601 XXX_37: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1633 XXX_38: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_TX_BU_ 506 : NEO,ADAS; -BO_TX_BU_ 780 : NEO,ADAS; -BO_TX_BU_ 829 : NEO,ADAS; -BO_TX_BU_ 927 : NEO,ADAS; - -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; +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_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB + + +BO_ 57 XXX_1: 3 XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" NEO + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO + +BO_ 145 XXX_2: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO + +BO_ 344 POWERTRAIN_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ ZEROS_BOH : 23|16@0+ (1,0) [0|15000] "" NEO + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 380 POWERTRAIN_DATA2: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 398 XXX_3: 3 XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 426 XXX_4: 8 VSA + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 476 XXX_5: 4 XXX + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX + +BO_ 487 XXX_6: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM + SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 507 XXX_7: 1 XXX + +BO_ 542 XXX_8: 7 XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 545 XXX_9: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@1+ (1,0) [0|15] "" XXX + +BO_ 660 SCM_COMMANDS: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@1+ (1,0) [0|15] "" XXX + +BO_ 661 XXX_10: 4 XXX + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX + +BO_ 662 CRUISE_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO + +BO_ 777 XXX_11: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +BO_ 800 XXX_12: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 804 CRUISE: 8 PCM + SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO + SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 808 XXX_13: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 871 XXX_14: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 882 XXX_15: 2 XXX + SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 XXX_16: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 891 XXX_17: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 918 XXX_18: 7 XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 923 XXX_19: 2 XXX + SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 ACC_HUD_2: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 929 XXX_20: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 983 XXX_21: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 985 XXX_22: 3 XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX + +BO_ 1024 XXX_23: 5 XXX + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX + +BO_ 1027 XXX_24: 5 XXX + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + +BO_ 1036 XXX_25: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1039 XXX_26: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1057 XXX_27: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1064 XXX_28: 7 XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 1088 XXX_29: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1089 XXX_30: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1108 XXX_31: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1125 XXX_32: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1296 XXX_33: 3 XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX + +BO_ 1365 XXX_34: 5 XXX + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX + +BO_ 1424 XXX_35: 5 XXX + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX + +BO_ 1600 XXX_36: 5 XXX + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX + +BO_ 1601 XXX_37: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1633 XXX_38: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_TX_BU_ 506 : NEO,ADAS; +BO_TX_BU_ 780 : NEO,ADAS; +BO_TX_BU_ 829 : NEO,ADAS; +BO_TX_BU_ 927 : NEO,ADAS; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_civic_hatchback_ex_2017_can.dbc b/opendbc/honda_civic_hatchback_ex_2017_can.dbc deleted file mode 100644 index e19f2e9139deb7..00000000000000 --- a/opendbc/honda_civic_hatchback_ex_2017_can.dbc +++ /dev/null @@ -1,463 +0,0 @@ -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_: EBCM NEO CAM RADAR PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" NEO - -BO_ 148 XXX_2: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 228 STEERING_CONTROL: 5 NEO - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS - -BO_ 232 XXX_3: 7 XXX - SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX - -BO_ 304 GAS_PEDAL: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO - SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 340 XXX_4: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 401 GEARBOX: 8 PCM - SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO - SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX - SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ USER_BRAKE : 7|16@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 427 XXX_5: 3 VSA - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX - -BO_ 428 XXX_6: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" NEO - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 441 XXX_7: 5 VSA - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 446 XXX_7: 3 VSA - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX - -BO_ 450 ELECTRONIC_PARKING_BRAKE: 8 EPB - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO - SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 470 XXX_8: 2 XXX - SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX - -BO_ 474 XXX_9: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 476 XXX_9: 7 XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 477 XXX_10: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 479 ACC_CONTROL: 8 NEO - SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM - SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX - SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX - SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM - SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX - SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 490 XXX_11: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 493 XXX_12: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 32|4@1+ (1,0) [0|15] "" XXX - -BO_ 495 ACC_CONTROL_ON: 8 XXX - SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX - SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 506 XXX_13: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 545 XXX_14: 6 SCM - SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX - SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 662 CRUISE_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 777 CAR_SPEED: 8 PCM - SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX - SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX - SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX - SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ BOH : 55|2@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 795 XXX_15: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 800 XXX_16: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 804 TRIP: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO - SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 808 XXX_17: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 814 XXX_18: 4 XXX - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ ZEROS_BOH : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_TO_1 : 0|1@0+ (1,0) [0|1] "" XXX - SG_ BOH_2 : 15|1@0+ (1,0) [0|1] "" XXX - SG_ SET_TO_ZERO : 20|3@0+ (1,0) [0|7] "" XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 884 STALK_STATUS_1: 8 XXX - SG_ LIGHT_SWITCH_AUTO : 46|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" XXX - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" NEO - -BO_ 927 RADAR_HUD: 8 RADAR - SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY - SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX - SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 929 XXX_23: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 985 XXX_24: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX - -BO_ 1024 XXX_25: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1027 XXX_26: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 1036 XXX_27: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1039 XXX_28: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1108 XXX_29: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1302 XXX_30: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1322 XXX_31: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1361 XXX_32: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1365 XXX_33: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1424 XXX_34: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1600 XXX_35: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1601 XXX_36: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1618 XXX_37: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1633 XXX_38: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1670 XXX_39: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - - -CM_ SG_ 344 DISTANCE_COUNTER ""; -CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; -CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; -CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; -CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; -CM_ SG_ 479 ZEROS_BOH "Signed value, negative when braking, positive when applying gas"; -CM_ SG_ 780 HUD_LEAD "0: blank, 1: no car, 2: car, 3: ACC Off"; -CM_ SG_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -CM_ SG_ 806 CMBS_STATES "3: Pressed, 2: On, 0: Off"; -CM_ SG_ 884 WIPER_SWITCH "0 = PARKED, 1 = INTERMITTENT, 2 = LOW, 3 = HIGH/QUICK WIPE"; -CM_ SG_ 891 HIGH_BEAMS "FLASH TO PASS OR FULL ON"; - -CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc new file mode 100644 index 00000000000000..bbf810dd7c4084 --- /dev/null +++ b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc @@ -0,0 +1,323 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _bosch_2018.dbc starts here" +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_ + +BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 330 STEERING_SENSORS: 8 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_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX + SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM + SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + + BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 804 CRUISE: 8 PCM + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +CM_ "honda_civic_hatchback_ex_2017_can.dbc starts here" + + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_civic_touring_2016_can_generated.dbc b/opendbc/honda_civic_touring_2016_can_generated.dbc new file mode 100644 index 00000000000000..841631bf603a17 --- /dev/null +++ b/opendbc/honda_civic_touring_2016_can_generated.dbc @@ -0,0 +1,372 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "honda_civic_touring_2016_can.dbc starts here" + + + +BO_ 148 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 330 STEERING_SENSORS: 8 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_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 6 XXX + SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 450 EPB_STATE "3 \"engaged\" 2 \"disengaging\" 1 \"engaging\" 0 \"disengaged\""; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_civic_touring_2016_can.dbc b/opendbc/honda_clarity_hybrid_2018_can.dbc similarity index 93% rename from opendbc/honda_civic_touring_2016_can.dbc rename to opendbc/honda_clarity_hybrid_2018_can.dbc index 24a498c0f03d44..86272de0bea3f2 100644 --- a/opendbc/honda_civic_touring_2016_can.dbc +++ b/opendbc/honda_clarity_hybrid_2018_can.dbc @@ -1,435 +1,433 @@ -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_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - -BO_ 148 XXX_2: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO - SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS - -BO_ 304 GAS_PEDAL2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO - SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ TRIP_DISTANCE : 55|8@0+ (0.010588,0) [0|255] "km" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 401 GEARBOX: 8 PCM - SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO - SG_ GEAR : 43|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 427 XXX_3: 3 VSA - SG_ CHECKSUM : 19|4@0+ (1,0) [0|6] "" NEO - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - -BO_ 428 XXX_4: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" NEO - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 450 XXX_5: 8 EPB - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO - SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 470 XXX_6: 2 VSA - SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 8|4@0+ (1,0) [0|3] "" NEO - -BO_ 476 XXX_7: 7 XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - -BO_ 487 XXX_8: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 493 XXX_9: 5 VSA - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM - SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM - SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM - SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM - -BO_ 512 GAS_COMMAND: 3 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 5 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - -BO_ 545 XXX_10: 6 XXX - SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" NEO - SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|6] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 662 CRUISE_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" NEO - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 777 XXX_11: 8 XXX - SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" NEO - SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 795 XXX_12: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 800 XXX_13: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO - SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 808 XXX_14: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 862 XXX_15: 8 ADAS - SG_ UI_ALERTS : 7|56@0+ (1,0) [0|127] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" NEO - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" NEO - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" NEO - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 891 XXX_17: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 927 XXX_19: 8 ADAS - SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY - SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY - SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY - SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY - SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY - SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 929 XXX_20: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 985 XXX_21: 3 XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - -BO_ 1024 XXX_22: 5 XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 1027 XXX_23: 5 XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1036 XXX_24: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1039 XXX_25: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1108 XXX_26: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1302 XXX_27: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1322 XXX_28: 5 XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 1361 XXX_29: 5 XXX - -BO_ 1365 XXX_30: 5 XXX - -BO_ 1424 XXX_31: 5 XXX - -BO_ 1600 XXX_32: 5 XXX - -BO_ 1601 XXX_33: 8 XXX - -BO_ 1633 XXX_34: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_TX_BU_ 228 : NEO,ADAS; -BO_TX_BU_ 506 : NEO,ADAS; -BO_TX_BU_ 780 : NEO,ADAS; -BO_TX_BU_ 829 : NEO,ADAS; -BO_TX_BU_ 862 : NEO,ADAS; -BO_TX_BU_ 927 : NEO,ADAS; - -CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; -CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; -VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; -VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; -VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; -VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; -CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; +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_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB + + +BO_ 57 XXX_1: 3 XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO + +BO_ 148 XXX_2: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO + SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 344 POWERTRAIN_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + SG_ TRIP_DISTANCE : 55|8@0+ (0.010588,0) [0|255] "km" NEO + +BO_ 380 POWERTRAIN_DATA2: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO + +BO_ 401 GEARBOX_1: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 420 VSA_STATUS: 8 VSA + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO + +BO_ 427 XXX_3: 3 VSA + SG_ CHECKSUM : 19|4@0+ (1,0) [0|6] "" NEO + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO + +BO_ 428 XXX_4: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" NEO + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO + +BO_ 450 XXX_5: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 476 XXX_7: 7 XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + +BO_ 487 XXX_8: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 493 XXX_9: 5 VSA + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 55|10@0+ (0.003906248,0) [0|0] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 11|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM + SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM + +BO_ 512 GAS_COMMAND: 3 NEO + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO + +BO_ 545 XXX_10: 5 XXX + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" NEO + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO + SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|6] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + +BO_ 662 CRUISE_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" NEO + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" NEO + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" NEO + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" NEO + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" NEO + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO + +BO_ 777 XXX_11: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" NEO + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 795 XXX_12: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 800 XXX_13: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" NEO + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 808 XXX_14: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 829 LKAS_HUD_2: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY + +BO_ 862 XXX_15: 8 ADAS + SG_ UI_ALERTS : 7|56@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" NEO + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" NEO + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" NEO + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + +BO_ 891 XXX_17: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + +BO_ 927 XXX_19: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 929 XXX_20: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 985 XXX_21: 3 XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO + +BO_ 1024 XXX_22: 5 XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO + +BO_ 1027 XXX_23: 5 XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 1036 XXX_24: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 1039 XXX_25: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 1108 XXX_26: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 1302 XXX_27: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 1322 XXX_28: 5 XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO + +BO_ 1361 XXX_29: 5 XXX + +BO_ 1365 XXX_30: 5 XXX + +BO_ 1424 XXX_31: 5 XXX + +BO_ 1600 XXX_32: 5 XXX + +BO_ 1601 XXX_33: 8 XXX + +BO_ 1633 XXX_34: 8 XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO + +BO_ 419 GEARBOX_2: 8 XXX + SG_ GEAR : 29|6@0+ (1,0) [0|63] "" NEO + SG_ GEAR_SHIFTER : 34|3@0+ (1,0) [0|7] "" NEO + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO + +BO_TX_BU_ 228 : NEO,ADAS; +BO_TX_BU_ 506 : NEO,ADAS; +BO_TX_BU_ 780 : NEO,ADAS; +BO_TX_BU_ 829 : NEO,ADAS; +BO_TX_BU_ 862 : NEO,ADAS; +BO_TX_BU_ 927 : NEO,ADAS; + + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_crv_ex_2017_can.dbc b/opendbc/honda_crv_ex_2017_can.dbc deleted file mode 100644 index d218ca5276b7a4..00000000000000 --- a/opendbc/honda_crv_ex_2017_can.dbc +++ /dev/null @@ -1,423 +0,0 @@ -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_: EBCM NEO CAM RADAR PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" NEO - -BO_ 148 XXX_2: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 228 STEERING_CONTROL: 5 NEO - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS - -BO_ 232 BRAKE_HOLD: 7 XXX - SG_ XMISSION_SPEED3 : 7|14@0- (1,0) [1|0] "" XXX - SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX - SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX - SG_ SET_TO_1 : 9|2@0- (1,0) [1|0] "" XXX - SG_ ZEROS_BOH2 : 28|5@0+ (1,0) [0|31] "" XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX - -BO_ 304 GAS_PEDAL: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO - SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 340 XXX_4: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 401 GEARBOX: 8 PCM - SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO - SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX - SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ USER_BRAKE : 7|16@0+ (0.015625,-103) [0|1000] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 427 XXX_5: 3 VSA - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 441 XXX_6: 5 VSA - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 446 XXX_7: 3 VSA - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX - -BO_ 450 ELECTRONIC_PARKING_BRAKE: 8 EPB - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO - SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 474 XXX_9: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 477 XXX_10: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 479 ACC_CONTROL: 8 NEO - SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM - SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX - SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX - SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM - SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX - SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 490 XXX_12: 8 XXX - SG_ BOH : 7|32@0+ (1,0) [0|65535] "" XXX - SG_ BOH_2 : 23|16@0+ (1,0) [0|65535] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 495 ACC_CONTROL_ON: 8 XXX - SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX - SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 545 XXX_14: 6 SCM - SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ WHEEL_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 662 CRUISE_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 777 CAR_SPEED: 8 PCM - SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX - SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX - SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX - SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ BOH : 55|2@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 800 XXX_16: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 804 TRIP: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_TEMPERATURE : 0|8@0+ (1,0) [0|65535] "" XXX - SG_ BOH_2 : 32|23@0+ (1,0) [0|255] "" NEO - SG_ BOH : 15|8@0+ (1,0) [0|255] "" XXX - SG_ BOOLEAN : 55|1@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO - SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 808 XXX_17: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 814 XXX_18: 4 XXX - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ ZEROS_BOH : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_TO_1 : 0|1@0+ (1,0) [0|1] "" XXX - SG_ BOH_2 : 15|1@0+ (1,0) [0|1] "" XXX - SG_ SET_TO_ZERO : 20|3@0+ (1,0) [0|7] "" XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_BOH_2 : 48|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 884 XXX_20: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 891 XXX_21: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 927 RADAR_HUD: 8 RADAR - SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY - SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX - SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 929 XXX_23: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 985 XXX_24: 3 XXX - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX - -BO_ 1024 XXX_25: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1027 XXX_26: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 1036 XXX_27: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1039 XXX_28: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1108 XXX_29: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1302 XXX_30: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1322 XXX_31: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1361 XXX_32: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1365 XXX_33: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1424 XXX_34: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1600 XXX_35: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1601 XXX_36: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1618 XXX_37: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - -BO_ 1633 XXX_38: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1670 XXX_39: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX - - - - -CM_ SG_ 344 DISTANCE_COUNTER ""; -CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; -CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; -CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; -CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; -CM_ SG_ 479 ZEROS_BOH "Signed value, negative when braking, positive when applying gas"; -CM_ SG_ 780 HUD_LEAD "0: blank, 1: no car, 2: car, 3: ACC Off"; -CM_ SG_ 806 CMBS_STATES "3: Pressed, 2: On, 0: Off"; - -CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_crv_ex_2017_can_generated.dbc b/opendbc/honda_crv_ex_2017_can_generated.dbc new file mode 100644 index 00000000000000..56a6b4e1b1c872 --- /dev/null +++ b/opendbc/honda_crv_ex_2017_can_generated.dbc @@ -0,0 +1,334 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _bosch_2018.dbc starts here" +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_ + +BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 330 STEERING_SENSORS: 8 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_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX + SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM + SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + + BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 804 CRUISE: 8 PCM + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +CM_ "honda_crv_ex_2017_can.dbc starts here" + + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 344 DISTANCE_COUNTER ""; +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; +CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; +CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; + +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_crv_touring_2016_can.dbc b/opendbc/honda_crv_touring_2016_can.dbc deleted file mode 100644 index 7b8c14168de58b..00000000000000 --- a/opendbc/honda_crv_touring_2016_can.dbc +++ /dev/null @@ -1,312 +0,0 @@ -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_: INTERCEPTOR EBCM NEO CAM PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - -BO_ 316 XXX_3: 8 PCM - -BO_ 340 XXX_4: 8 PCM - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 398 XXX_5: 3 PCM - -BO_ 399 STEER_STATUS: 6 EPS - SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" NEO - SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 401 GEARBOX: 8 PCM - SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO - SG_ GEAR : 35|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 404 STEERING_CONTROL: 4 NEO - SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS - SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" EPS - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" EPS - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 426 XXX_6: 8 VSA - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 474 XXX_7: 5 VSA - -BO_ 476 XXX_8: 5 XXX - -BO_ 487 XXX_9: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 493 XXX_10: 3 VSA - -BO_ 506 BRAKE_COMMAND: 8 NEO - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM - SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM - SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM - SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM - -BO_ 507 XXX_11: 1 NEO - -BO_ 542 XXX_12: 7 XXX - -BO_ 545 XXX_13: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 661 XXX_14: 4 XXX - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 777 XXX_15: 8 XXX - -BO_ 780 ACC_HUD: 8 CAM - SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY - -BO_ 800 XXX_16: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO - SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 808 XXX_17: 8 XXX - -BO_ 829 LKAS_HUD_2: 5 CAM - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 882 XXX_18: 2 XXX - -BO_ 884 XXX_19: 7 XXX - -BO_ 888 XXX_20: 8 XXX - -BO_ 891 XXX_21: 8 XXX - -BO_ 923 XXX_23: 2 XXX - -BO_ 929 XXX_24: 8 XXX - -BO_ 983 XXX_25: 8 XXX - -BO_ 985 XXX_26: 3 XXX - -BO_ 1024 XXX_27: 5 XXX - -BO_ 1027 XXX_28: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 1033 XXX_29: 5 XXX - -BO_ 1036 XXX_30: 8 XXX - -BO_ 1039 XXX_31: 8 XXX - -BO_ 1057 XXX_32: 5 XXX - -BO_ 1064 XXX_32: 7 XXX - -BO_ 1108 XXX_33: 8 XXX - -BO_ 1125 XXX_34: 8 XXX - -BO_ 1296 XXX_35: 8 XXX - -BO_ 1365 XXX_36: 5 XXX - -BO_ 1424 XXX_37: 5 XXX - -BO_ 1600 XXX_38: 5 XXX - -BO_ 1601 XXX_39: 8 XXX - -BO_TX_BU_ 399 : NEO,CAM; -BO_TX_BU_ 506 : NEO,CAM; -BO_TX_BU_ 780 : NEO,CAM; -BO_TX_BU_ 829 : NEO,CAM; - -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_crv_touring_2016_can_generated.dbc b/opendbc/honda_crv_touring_2016_can_generated.dbc new file mode 100644 index 00000000000000..3fa85d899637a4 --- /dev/null +++ b/opendbc/honda_crv_touring_2016_can_generated.dbc @@ -0,0 +1,304 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_fit_ex_2018_can_generated.dbc b/opendbc/honda_fit_ex_2018_can_generated.dbc new file mode 100644 index 00000000000000..2e7c7fb559a554 --- /dev/null +++ b/opendbc/honda_fit_ex_2018_can_generated.dbc @@ -0,0 +1,326 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "honda_fit_ex_2018_can.dbc starts here" + + + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_odyssey_exl_2018.dbc b/opendbc/honda_odyssey_exl_2018_generated.dbc similarity index 63% rename from opendbc/honda_odyssey_exl_2018.dbc rename to opendbc/honda_odyssey_exl_2018_generated.dbc index cab4acab1cb984..05dd1a43630360 100644 --- a/opendbc/honda_odyssey_exl_2018.dbc +++ b/opendbc/honda_odyssey_exl_2018_generated.dbc @@ -1,72 +1,69 @@ -VERSION "" +CM_ "AUTOGENERATED FILE, DO NOT EDIT" -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_: EBCM EON CAM PCM EPS VSA SCM BDY XXX - - -BO_ 57 XXX_1: 3 XXX - -BO_ 148 XXX_2: 8 XXX - -BO_ 228 STEERING_CONTROL: 5 CAM - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR -BO_ 229 XXX_3: 4 XXX - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - -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 +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 380 POWERTRAIN_DATA2: 8 PCM +BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON @@ -79,110 +76,76 @@ BO_ 380 POWERTRAIN_DATA2: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 411 XXX_4: 5 XXX - -BO_ 419 GEARBOX: 8 PCM - SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON - SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX - -BO_ 427 XXX_5: 3 XXX - BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON -BO_ 450 XXX_6: 8 XXX - SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX - SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 463 XXX_7: 8 XXX - BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 476 XXX_8: 4 XXX - BO_ 490 VEHICLE_DYNAMICS: 8 VSA SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 506 BRAKE_COMMAND: 8 CAM - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM - -BO_ 542 XXX_9: 7 XXX - -BO_ 545 XXX_10: 4 XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" EON - -BO_ 662 CRUISE_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 773 SEATBELT_STATUS: 7 BDY SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON -BO_ 777 XXX_11: 8 XXX +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 780 ACC_HUD: 8 CAM - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY @@ -199,13 +162,11 @@ BO_ 780 ACC_HUD: 8 CAM SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY -BO_ 795 XXX_12: 8 XXX - -BO_ 800 XXX_13: 8 XXX - BO_ 804 CRUISE: 8 PCM SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON @@ -216,28 +177,10 @@ BO_ 804 CRUISE: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON - SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 808 XXX_14: 8 XXX - -BO_ 817 XXX_15: 4 XXX - -BO_ 819 XXX_16: 7 XXX - -BO_ 821 XXX_17: 5 XXX - -BO_ 825 XXX_18: 4 XXX - -BO_ 829 LKAS_HUD: 5 CAM +BO_ 829 LKAS_HUD: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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 @@ -245,6 +188,7 @@ BO_ 829 LKAS_HUD: 5 CAM 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_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY @@ -252,63 +196,12 @@ BO_ 829 LKAS_HUD: 5 CAM SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 837 XXX_19: 5 XXX - -BO_ 856 XXX_20: 7 XXX - -BO_ 862 XXX_21: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 871 XXX_22: 8 XXX - -BO_ 881 XXX_23: 8 XXX - -BO_ 882 XXX_24: 4 XXX - -BO_ 884 XXX_25: 8 XXX - -BO_ 891 XXX_26: 8 XXX + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON - -BO_ 905 XXX_27: 8 XXX - -BO_ 923 XXX_28: 2 XXX - -BO_ 927 ACC_HUD_2: 8 CAM - SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY - SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY - SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY - SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY - SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY - SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 929 XXX_29: 8 XXX - -BO_ 963 XXX_30: 8 XXX - -BO_ 965 XXX_31: 8 XXX - -BO_ 966 XXX_32: 8 XXX - -BO_ 967 XXX_33: 8 XXX - -BO_ 983 XXX_34: 8 XXX - -BO_ 985 XXX_35: 3 XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON BO_ 1029 DOORS_STATUS: 8 BDY SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON @@ -319,68 +212,132 @@ BO_ 1029 DOORS_STATUS: 8 BDY SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 1036 XXX_36: 8 XXX - -BO_ 1052 XXX_37: 8 XXX - -BO_ 1064 XXX_38: 7 XXX - -BO_ 1088 XXX_39: 8 XXX - -BO_ 1089 XXX_40: 8 XXX +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; -BO_ 1092 XXX_41: 1 XXX -BO_ 1108 XXX_42: 8 XXX +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; -BO_ 1110 XXX_43: 8 XXX +CM_ "honda_odyssey_exl_2018.dbc starts here" -BO_ 1125 XXX_44: 8 XXX -BO_ 1296 XXX_45: 8 XXX -BO_ 1302 XXX_46: 8 XXX +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS -BO_ 1600 XXX_47: 5 XXX +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON -BO_ 1601 XXX_48: 8 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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON -BO_ 1612 XXX_49: 5 XXX +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON -BO_ 1613 XXX_50: 5 XXX +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 1614 XXX_51: 5 XXX +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX -BO_ 1615 XXX_52: 8 XXX +BO_ 450 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX -BO_ 1616 XXX_53: 5 XXX +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON -BO_ 1619 XXX_54: 5 XXX +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 1623 XXX_55: 5 XXX +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1668 XXX_56: 5 XXX +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_TX_BU_ 228 : EON,CAM; -BO_TX_BU_ 506 : EON,CAM; -BO_TX_BU_ 780 : EON,CAM; -BO_TX_BU_ 829 : EON,CAM; -BO_TX_BU_ 862 : EON,CAM; -BO_TX_BU_ 927 : EON,CAM; +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; -CM_ SG_ 450 EPB_STATE "3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged""; -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; -VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; + CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_odyssey_extreme_edition_2018_china_can.dbc b/opendbc/honda_odyssey_extreme_edition_2018_china_can.dbc new file mode 100644 index 00000000000000..ad66716f35cc01 --- /dev/null +++ b/opendbc/honda_odyssey_extreme_edition_2018_china_can.dbc @@ -0,0 +1,295 @@ +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_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON INTERCEPTOR + + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + SG_ ZEROS : 23|16@0+ (1,0) [0|15000] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ BOH2 : 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + 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 + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-2985|2985] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ STEER_STATUS : 43|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + SG_ STEER_TORQUE : 7|16@0- (-1,0) [-32767|32767] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ DRIVERS_DOOR_OPEN : 63|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + + + + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_pilot_touring_2017_can.dbc b/opendbc/honda_pilot_touring_2017_can.dbc deleted file mode 100644 index 459109c6dfaf32..00000000000000 --- a/opendbc/honda_pilot_touring_2017_can.dbc +++ /dev/null @@ -1,322 +0,0 @@ -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_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS - -BO_ 304 GAS_PEDAL2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 398 XXX_3: 3 XXX - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 419 GEARBOX: 8 PCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" NEO - SG_ GEAR : 7|8@0+ (1,0) [0|255] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 428 XXX_4: 8 XXX - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 476 XXX_5: 4 XXX - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM - -BO_ 512 GAS_COMMAND: 3 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 5 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - -BO_ 542 XXX_6: 7 XXX - -BO_ 545 XXX_7: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 777 XXX_8: 8 XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ HUD_DISTANCE_3 : 52|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|3] "" BDY - -BO_ 800 XXX_9: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 808 XXX_10: 8 XXX - -BO_ 819 XXX_11: 7 XXX - -BO_ 821 XXX_12: 5 XXX - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" 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_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 882 XXX_13: 2 XXX - -BO_ 884 XXX_14: 7 XXX - -BO_ 887 XXX_15: 8 XXX - -BO_ 888 XXX_16: 8 XXX - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - -BO_ 923 XXX_18: 2 XXX - -BO_ 929 XXX_19: 4 XXX - -BO_ 983 XXX_20: 8 XXX - -BO_ 985 XXX_21: 3 XXX - -BO_ 1024 XXX_22: 5 XXX - -BO_ 1027 XXX_23: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1030 XXX_24: 5 VSA - -BO_ 1034 XXX_25: 5 XXX - -BO_ 1036 XXX_26: 8 XXX - -BO_ 1039 XXX_27: 8 XXX - -BO_ 1057 XXX_28: 5 EPS - -BO_ 1064 XXX_29: 7 XXX - -BO_ 1108 XXX_30: 8 XXX - -BO_ 1365 XXX_31: 5 XXX - -BO_ 1600 XXX_32: 5 XXX - -BO_ 1601 XXX_33: 8 XXX - -BO_TX_BU_ 228 : NEO,ADAS; -BO_TX_BU_ 506 : NEO,ADAS; -BO_TX_BU_ 780 : NEO,ADAS; -BO_TX_BU_ 829 : NEO,ADAS; - - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; -VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; -VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; -VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_pilot_touring_2017_can_generated.dbc b/opendbc/honda_pilot_touring_2017_can_generated.dbc new file mode 100644 index 00000000000000..0c43f98f34b3d9 --- /dev/null +++ b/opendbc/honda_pilot_touring_2017_can_generated.dbc @@ -0,0 +1,296 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "honda_pilot_touring_2017_can.dbc starts here" + + + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc new file mode 100644 index 00000000000000..a8a97d7f1f20f5 --- /dev/null +++ b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc @@ -0,0 +1,291 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +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_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|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|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 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_ 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_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "honda_ridgeline_black_edition_2017_can.dbc starts here" + + + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +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_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/hyundai_2015_ccan.dbc b/opendbc/hyundai_2015_ccan.dbc new file mode 100644 index 00000000000000..addc0cac31fa08 --- /dev/null +++ b/opendbc/hyundai_2015_ccan.dbc @@ -0,0 +1,1416 @@ +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_: IAP ODS _4WD BCM HUD DATC MDPS AAF_Tester AEMC SMK _4WD EPB CUBIS MTS TMU EVP CGW TPMS LPI DI_BOX SPAS EMS LCA TCU IBOX FATC AFLS FPCM SCC AHLS AVM ABS SNV OPI PGS SAS AAF Dummy LDWS_LKAS LVR ESC PSB CLU ECS ACU REA + +BO_ 1532 ODS13: 5 ODS + SG_ CR_Ods_ID : 0|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_Chksum_H : 8|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_Chksum_L : 16|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_RomID_H : 24|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_RomID_L : 32|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + +BO_ 1531 ODS12: 8 ODS + SG_ CR_Ods_SerNum0 : 0|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum3 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum4 : 32|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum5 : 40|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum6 : 48|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum7 : 56|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + +BO_ 1530 ODS11: 8 ODS + SG_ CF_Ods_PrcCmd : 1|1@1+ (1.0,0.0) [0.0|1.0] "" Dummy + SG_ CF_Ods_BtsFail : 3|1@1+ (1.0,0.0) [0.0|1.0] "" Dummy + SG_ CF_Ods_AcuRcvSN : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_EolCal : 5|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_PsFail : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_EcuFail : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_WgtStat : 8|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_OccStat : 16|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CR_Wcs_ErrStat : 32|8@1+ (1.0,0.0) [0.0|63.0] "" ACU + SG_ CR_Wcs_ClassStat : 40|8@1+ (1.0,0.0) [0.0|4.0] "" ACU,BCM + +BO_ 1017 ECS12: 4 ECS + SG_ Height_FL : 0|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_FR : 8|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_RL : 16|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_RR : 24|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + +BO_ 1268 SPAS12: 8 SPAS + SG_ CF_Spas_HMI_Stat : 0|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Spas_Disp : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS + SG_ CF_Spas_FIL_Ind : 10|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FIR_Ind : 13|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FOL_Ind : 16|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FOR_Ind : 19|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_VolDown : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RIL_Ind : 24|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_RIR_Ind : 27|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FLS_Alarm : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_ROL_Ind : 32|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_ROR_Ind : 35|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FCS_Alarm : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_FI_Ind : 40|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_RI_Ind : 43|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FRS_Alarm : 46|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_FR_Alarm : 48|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Spas_RR_Alarm : 50|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Spas_BEEP_Alarm : 52|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Spas_StatAlarm : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Spas_RLS_Alarm : 57|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RCS_Alarm : 59|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RRS_Alarm : 61|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1265 CLU11: 4 CLU + SG_ CF_Clu_CruiseSwState : 0|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_CruiseSwMain : 3|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_SldMainSW : 4|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Clu_ParityBit1 : 5|1@1+ (1.0,0.0) [0.0|1.0] "pulse count" EMS + SG_ CF_Clu_VanzDecimal : 6|2@1+ (0.125,0.0) [0.0|0.375] "" EMS + SG_ CF_Clu_Vanz : 8|9@1+ (0.5,0.0) [0.0|255.5] "km/h or MPH" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_SPEED_UNIT : 17|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_DetentOut : 18|1@1+ (1.0,0.0) [0.0|1.0] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_RheostatLevel : 19|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_CluInfo : 24|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_AmpInfo : 25|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_AliveCnt1 : 28|4@1+ (1.0,0.0) [0.0|15.0] "" AHLS,EMS,EPB,LDWS_LKAS,MDPS,SCC + +BO_ 1492 TMU_GW_PE_01: 8 CLU + SG_ TMU_IVRActivity : 0|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ TMU_PhoneActivity : 2|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1491 HU_DATC_PE_00: 8 CLU + SG_ HU_VRActivity : 0|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ HU_PhoneActivity : 2|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ BlowerNoiseControl : 4|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1490 HU_DATC_E_02: 8 CLU + SG_ HU_DATC_RearOnOffSet : 6|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ HU_DATC_ADSOnOffSet : 8|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1479 EMS21: 8 EMS + SG_ SCR_LEVEL_WARN_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ SCR_LEVEL_WARN : 1|3@1+ (1.0,0.0) [0.0|4.0] "" CLU + SG_ SCR_SYS_ERROR_WARN : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ SCR_SYSTEM_WARN_LAMP : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ SCR_INDUCEMENT_EXIT_COND : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ SCR_UREA_LEVEL : 16|8@1+ (0.5,0.0) [0.0|100.0] "%" CLU + SG_ SCR_NO_REMAINING_RESTARTS : 24|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ SCR_REMAINING_DISTANCE : 32|16@1+ (1.0,0.0) [0.0|25000.0] "km" CLU + +BO_ 1472 GW_Warning_PE: 8 BCM + SG_ Audio_VolumeDown : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Flh_Alarm : 48|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Fcnt_Alarm : 50|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Frh_Alarm : 52|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Rlh_Alarm : 56|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,PGS + SG_ Pas_Spkr_Rcnt_Alarm : 58|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Rrh_Alarm : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,PGS + +BO_ 1984 CAL_SAS11: 2 ESC + SG_ CCW : 0|4@1+ (1.0,0.0) [0.0|15.0] "" SAS + SG_ SAS_CID : 4|11@1+ (1.0,0.0) [0.0|2047.0] "" SAS + +BO_ 1456 CLU12: 4 CLU + SG_ CF_Clu_Odometer : 0|24@1+ (0.1,0.0) [0.0|1677721.4] "km" _4WD,AAF,BCM,CUBIS,EMS,EPB,IBOX,LDWS_LKAS,SCC,TPMS + +BO_ 688 SAS11: 5 MDPS + SG_ SAS_Angle : 0|16@1- (0.1,0.0) [-3276.8|3276.7] "Deg" _4WD,ACU,AFLS,AVM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU,_4WD,ACU,AFLS,AVM,BCM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU + SG_ SAS_Speed : 16|8@1+ (4.0,0.0) [0.0|1016.0] "" AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU,AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU + SG_ SAS_Stat : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ MsgCount : 32|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + SG_ CheckSum : 36|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + +BO_ 1441 ACU12: 8 ACU + SG_ CR_Acu_SN : 0|64@1+ (1.0,0.0) [0.0|0.0] "" ODS + +BO_ 1440 ACU11: 8 ACU + SG_ CF_Ods_SNRcv : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Ods_IDRcv : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Ods_RZReq : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Abg_DepInhEnt : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Abg_DepEnt : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_PasBkl_FltStat : 28|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_DriBkl_FltStat : 29|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_PasBkl_Stat : 30|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,ODS,PSB,TMU + SG_ CF_DriBkl_Stat : 31|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_SWL_Ind : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CUBIS,IBOX + SG_ CF_Acu_FltStat : 34|2@1+ (1.0,0.0) [0.0|3.0] "" CUBIS,IBOX + SG_ CF_Acu_ExtOfSab : 36|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,CUBIS,IBOX + SG_ CF_Acu_Dtc : 40|16@1+ (1.0,0.0) [0.0|65535.0] "" CUBIS,IBOX + SG_ CF_Acu_NumOfFlt : 56|8@1+ (1.0,0.0) [0.0|255.0] "" CUBIS,IBOX + +BO_ 1437 AHLS11: 8 AHLS + SG_ CF_Ahls_WarnLamp : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Ahls_WarnMsg : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1434 PSB11: 2 PSB + SG_ PSB_LH_FAIL : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PSB_LH_TGL : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ PSB_LH_ACT : 3|4@1+ (1.0,0.0) [0.0|4.0] "" Dummy + SG_ PSB_RH_FAIL : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PSB_RH_TGL : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ PSB_RH_ACT : 11|4@1+ (1.0,0.0) [0.0|4.0] "" Dummy + +BO_ 916 TCS13: 8 ESC + SG_ aBasis : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ BrakeLight : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,SCC + SG_ DCEnable : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ AliveCounterTCS : 13|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,SCC + SG_ ACCReqLim : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ TQI_ACC : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS + SG_ ACCEL_REF_ACC : 32|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ ACCEnable : 43|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ DriverOverride : 45|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ StandStill : 47|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ CheckSum_TCS3 : 48|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,SCC + SG_ ACC_EQUIP : 52|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ PBRAKE_ACT : 53|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ ACC_REQ : 54|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ DriverBraking : 55|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ CF_VSM_Coded : 56|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_VSM_Avail : 57|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,SCC + SG_ CF_VSM_Handshake : 59|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_DriBkeStat : 60|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_VSM_ConfSwi : 61|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ AEB_EQUIP : 63|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + +BO_ 1427 TPMS11: 6 BCM + SG_ TPMS_W_LAMP : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ TREAD_W_LAMP : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ POS_FL_W_LAMP : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_FR_W_LAMP : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RL_W_LAMP : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RR_W_LAMP : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ STATUS_TPMS : 8|3@1+ (1.0,0.0) [0.0|0.0] "" CLU + SG_ UNIT : 11|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PRESSURE_FL : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_FR : 24|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_RL : 32|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_RR : 40|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + +BO_ 915 TCS12: 4 ESC + SG_ SA_COUNT : 0|16@1+ (2.0,-32768.0) [-32768.0|98302.0] "" _4WD,ACU,MDPS + SG_ SA_Z_COUNT : 16|15@1+ (2.0,-32768.0) [-32768.0|32766.0] "" _4WD,ACU,MDPS + SG_ SA_Z_FLAG : 31|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,MDPS + +BO_ 1170 EMS19: 8 EMS + SG_ CF_Ems_BrkReq : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX,TCU + SG_ CF_Ems_DnShftReq : 1|4@1+ (1.0,0.0) [0.0|14.0] "" IBOX,TCU + SG_ CF_Ems_RepModChk : 5|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ CF_Ems_AAFOpenReq : 7|1@1+ (1.0,0.0) [0.0|1.0] "" AAF,IBOX + SG_ CF_Ems_DecelReq : 8|12@1+ (0.0010,-4.094) [-4.094|0.0] "m/s^2" ESC,IBOX,TCU + SG_ CR_Ems_BstPre : 20|12@1+ (1.322,0.0) [0.0|4094.0] "hPa" CLU,IBOX + SG_ CR_Ems_EngOilTemp : 32|8@1+ (0.75,-40.0) [0.0|254.0] "deg" CLU,IBOX + SG_ DPF_LAMP_STAT : 40|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ BAT_LAMP_STAT : 42|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_ModeledAmbTemp : 48|8@1+ (0.5,-41.0) [-41.0|85.5] "deg" AAF,IBOX + SG_ CF_Ems_OPSFail : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_AliveCounterEMS9 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + SG_ CF_Ems_ChecksumEMS9 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + +BO_ 1425 AFLS11: 2 AFLS + SG_ AFLS_STAT : 1|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Afls_TrfChgStat : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Afls_LedHLStat : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 912 SPAS11: 7 SPAS + SG_ CF_Spas_Stat : 0|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,MDPS + SG_ CF_Spas_TestMode : 4|2@1+ (1.0,0.0) [0.0|3.0] "" MDPS + SG_ CR_Spas_StrAngCmd : 8|16@1- (0.1,0.0) [-3276.8|3276.7] "" MDPS + SG_ CF_Spas_BeepAlarm : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Spas_Mode_Seq : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_AliveCnt : 32|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Spas_Chksum : 40|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Spas_PasVol : 48|3@1+ (1.0,0.0) [0.0|7.0] "" CGW,CLU + +BO_ 1168 EPB11: 7 EPB + SG_ EPB_I_LAMP : 0|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU,CUBIS,ESC,IBOX + SG_ EPB_F_LAMP : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,ESC,IBOX + SG_ EPB_ALARM : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ EPB_CLU : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,ESC + SG_ EPB_SWITCH : 16|2@1+ (1.0,0.0) [0.0|3.0] "" ESC,SCC + SG_ EPB_RBL : 18|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,ESC + SG_ EPB_STATUS : 19|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,ESC,SCC,TCU + SG_ EPB_FRC_ERR : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,SCC,TCU + SG_ EPB_DBF_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ ESP_ACK : 25|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ EPB_DBF_REQ : 26|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ EPB_FAIL : 29|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,SCC + SG_ EPB_FORCE : 32|12@1+ (1.0,-1000.0) [-1000.0|3000.0] "" ESC + SG_ EPB_DBF_DECEL : 48|8@1+ (0.01,0.0) [0.0|2.54] "g" ESC + +BO_ 399 EMS_H12: 8 EMS + SG_ R_TqAcnApvC : 0|8@1+ (0.2,0.0) [0.0|51.0] "Nm" DATC,IBOX + SG_ R_PAcnC : 8|8@1+ (125.0,0.0) [0.0|31875.0] "hPa" DATC,IBOX + SG_ TQI_B : 16|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ABS,ESC,IBOX + SG_ SLD_VS : 24|8@1+ (1.0,0.0) [0.0|255.0] "km/h" CLU,IBOX + SG_ CF_CdaStat : 32|3@1+ (1.0,0.0) [0.0|7.0] "" AEMC,IBOX,TCU + SG_ CF_Ems_IsgStat : 35|3@1+ (1.0,0.0) [0.0|7.0] "" ABS,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,MDPS,SMK,TCU + SG_ CF_Ems_OilChg : 38|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_EtcLimpMod : 39|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ R_NEngIdlTgC : 40|8@1+ (10.0,0.0) [0.0|2550.0] "rpm" DATC,IBOX,TCU + SG_ CF_Ems_UpTarGr : 48|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_DownTarGr : 49|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_DesCurGr : 50|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX + SG_ CF_Ems_SldAct : 54|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_SldPosAct : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_HPresStat : 56|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ CF_Ems_IsgBuz : 57|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_IdlStpFCO : 58|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_FCopen : 59|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_ActEcoAct : 60|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ CF_Ems_EngRunNorm : 61|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,IBOX,TCU + SG_ CF_Ems_IsgStat2 : 62|2@1+ (2.0,0.0) [0.0|3.0] "" CLU,IBOX,TCU + +BO_ 1419 LCA11: 8 LCA + SG_ CF_Lca_Stat : 0|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Rcta_Stat : 4|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Lca_IndLeft : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Rcw_Stat : 10|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_RCW_Warning : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Lca_IndRight : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Lca_SndWan_Stat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_FR_SndWan : 20|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_FL_SndWan : 21|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_RR_SndWan : 22|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_RL_SndWan : 23|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_Lca_IndBriLeft : 24|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_Lca_IndBriRight : 32|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndBriLeft : 40|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndBriRight : 48|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndLeft : 56|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_RCTA_IndRight : 58|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_SndWarnForClu : 60|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 906 ABS11: 8 ABS + SG_ ABS_DEF : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,EMS,SPAS,TCU + SG_ EBD_DEF : 1|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,SPAS,TCU + SG_ ABS_ACT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,EPB,SPAS,TCU + SG_ ABS_W_LAMP : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,CUBIS,MTS,TMU + SG_ EBD_W_LAMP : 4|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ ABS_DIAG : 5|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ ESS_STAT : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,BCM,CLU,EMS + +BO_ 903 WHL_PUL11: 6 ABS + SG_ WHL_PUL_FL : 0|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_FR : 8|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RL : 16|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RR : 24|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_DIR_FL : 32|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_FR : 34|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RL : 36|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RR : 38|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_PUL_Chksum : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EPB,SPAS,TPMS,EPB,LCA,LDWS_LKAS,SPAS,TPMS + +BO_ 1415 TMU11: 8 IBOX + SG_ CF_Tmu_VehSld : 0|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Tmu_VehImmo : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Tmu_ReqRepCnd : 2|2@1+ (1.0,0.0) [0.0|3.0] "" EMS + SG_ CF_Tmu_AirconCtr : 4|1@1+ (1.0,0.0) [0.0|1.0] "" DATC + SG_ CF_Tmu_TempMd : 5|1@1+ (1.0,0.0) [0.0|1.0] "" DATC + SG_ CF_Tmu_TempSet : 6|16@1+ (1.0,0.0) [0.0|20.0] "" DATC + SG_ CF_Tmu_DefrostCtr : 22|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,FATC + SG_ CF_Tmu_AliveCnt1 : 56|4@1+ (1.0,0.0) [0.0|15.0] "" EMS + +BO_ 902 WHL_SPD11: 8 ABS + SG_ WHL_SPD_FL : 0|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_FR : 16|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,ACU,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RL : 32|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,BCM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,BCM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RR : 48|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_AliveCounter_LSB : 14|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_AliveCounter_MSB : 30|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_LSB : 46|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_MSB : 62|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1414 EVP11: 3 EVP + SG_ CF_Evp_Stat : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1412 AAF11: 8 AAF + SG_ CF_Aaf_ActFlapStatus : 0|2@1+ (1.0,0.0) [0.0|3.0] "" AAF_Tester + SG_ CF_Aaf_ModeStatus : 2|3@1+ (1.0,0.0) [0.0|7.0] "" AAF_Tester + SG_ CF_Aaf_WrnLamp : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Aaf_ErrStatus : 6|10@1+ (1.0,0.0) [0.0|1023.0] "" AAF_Tester,EMS + SG_ CF_Aaf_OpenRqSysAct : 16|8@1+ (1.0,0.0) [0.0|255.0] "" AAF_Tester + SG_ CF_Aaf_PStatus : 24|8@1+ (1.0,0.0) [0.0|100.0] "%" AAF_Tester + SG_ CF_Aaf_OpenRqSysSol : 32|8@1+ (1.0,0.0) [0.0|255.0] "" AAF_Tester + SG_ CF_Aaf_SolFlapStatus : 40|2@1+ (1.0,0.0) [0.0|3.0] "" AAF_Tester + SG_ CF_Aaf_MilOnReq : 42|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 900 EMS17: 8 EMS + SG_ CF_Ems_PkpCurMSV : 0|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_HolCurMSV : 8|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_InjVBnkAct : 16|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_InjVActSet : 24|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_DiagFulHDEV : 32|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_SwiOffIC1 : 33|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_SwiOffIC2 : 34|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_DiagReqHDEV : 38|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CR_Ems_DutyCycMSV : 40|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" DI_BOX + SG_ CR_Ems_BatVolRly : 48|8@1+ (0.1,0.0) [0.0|25.5] "V" DI_BOX + +BO_ 387 REA11: 8 REA + SG_ CF_EndBst_PwmDuH : 0|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PwmDuL : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PwmFqOutRng : 2|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_HbriOverCur : 3|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_HbriOverTemp : 4|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PosSnsKOR : 6|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PosSnsOSOR : 7|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_EepFlt : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_RomFlt : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_RamFlt : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_CanFlt : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_AgH : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_AgL : 13|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_ORVol : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CR_EndBst_ActPos : 16|16@1+ (0.117,0.0) [1.989|118.053] "" EMS + SG_ CR_EndBst_DemPos : 32|16@1+ (0.117,0.0) [0.0|119.691] "" EMS + SG_ CR_EndBst_HbriPwr : 48|16@1+ (0.045,0.0) [0.0|99.99] "%" EMS + +BO_ 1411 CUBIS11: 8 CUBIS + SG_ CF_Cubis_HUDisp : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + +BO_ 899 FATC11: 8 DATC + SG_ CR_Fatc_TqAcnOut : 0|8@1+ (0.2,0.0) [0.0|50.8] "Nm" EMS,IBOX + SG_ CF_Fatc_AcnRqSwi : 8|1@1+ (1.0,0.0) [0.0|1.0] "" AAF,EMS,IBOX + SG_ CF_Fatc_AcnCltEnRq : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_EcvFlt : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_BlwrOn : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_FATC_Iden : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Fatc_BlwrMax : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX + SG_ CF_Fatc_EngStartReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_IsgStopReq : 16|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_CtrInf : 17|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,IBOX + SG_ CF_Fatc_MsgCnt : 20|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + SG_ CR_Fatc_OutTemp : 24|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" BCM,CLU,EMS,IBOX,SPAS,TCU,TPMS + SG_ CR_Fatc_OutTempSns : 32|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" AAF,AHLS,CLU,EMS,IBOX,SPAS,TCU + SG_ CF_Fatc_Compload : 40|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,IBOX + SG_ CF_Fatc_ActiveEco : 43|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Fatc_AutoActivation : 44|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX + SG_ CF_Fatc_DefSw : 45|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,IBOX + SG_ CF_Fatc_PtcRlyStat : 46|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_ChkSum : 56|8@1+ (1.0,0.0) [0.0|255.0] "" EMS,IBOX,SPAS + +BO_ 129 EMS_DCT12: 8 EMS + SG_ CR_Ems_SoakTimeExt : 0|6@1+ (5.0,0.0) [0.0|315.0] "Min" TCU + SG_ BRAKE_ACT : 6|2@1+ (1.0,0.0) [0.0|3.0] "" TCU + SG_ CF_Ems_EngOperStat : 8|8@1+ (1.0,0.0) [0.0|255.0] "" TCU + SG_ CR_Ems_IndAirTemp : 16|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" TCU + SG_ CF_Ems_Alive2 : 56|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Ems_ChkSum2 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 897 MDPS11: 8 MDPS + SG_ CF_Mdps_WLmp : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,EMS,IBOX,SPAS + SG_ CF_Mdps_Flex : 2|3@1+ (1.0,0.0) [0.0|3.0] "" CLU,LDWS_LKAS + SG_ CF_Mdps_FlexDisp : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Mdps_Stat : 7|4@1+ (1.0,0.0) [0.0|15.0] "" SPAS + SG_ CR_Mdps_DrvTq : 11|12@1+ (0.01,-20.48) [-20.48|20.46] "" SPAS + SG_ CF_Mdps_ALTRequest : 23|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CR_Mdps_StrAng : 24|16@1- (0.1,0.0) [-3276.8|3276.7] "Deg" SPAS + SG_ CF_Mdps_AliveCnt : 40|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_Chksum : 48|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_SPAS_FUNC : 57|1@1+ (1.0,0.0) [0.0|1.0] "flag" SPAS + SG_ CF_Mdps_LKAS_FUNC : 58|1@1+ (1.0,0.0) [0.0|1.0] "flag" LDWS_LKAS + SG_ CF_Mdps_CurrMode : 59|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Mdps_Type : 61|2@1+ (1.0,0.0) [0.0|2.0] "" LDWS_LKAS,SPAS + +BO_ 896 DI_BOX13: 8 DI_BOX + SG_ CF_DiBox_HPreInjVConfStat : 0|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVStat1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVStat2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVPkp : 24|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVBpt : 32|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_ErrRegFrtMSV : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_ErrRegSedMSV : 48|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SPIErrSedMSV : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_SPIErrFrtMSV : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IDErrSedMSV : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IDErrFrtMSV : 59|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IniStatMSV : 60|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 640 EMS13: 8 EMS + SG_ LV_FUEL_TYPE_ECU : 0|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,LPI,SMK + SG_ LV_BFS_CFIRM : 1|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_CRASH : 2|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_VB_OFF_ACT : 3|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_GSL_MAP M : 4|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_ENG_TURN : 5|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ ERR_FUEL : 8|8@1+ (1.0,0.0) [0.0|255.0] "" LPI + SG_ EOS : 16|8@1+ (1.0,0.0) [0.0|255.0] "" LPI + SG_ TCO : 24|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" LPI + SG_ N_32 : 32|8@1+ (32.0,0.0) [0.0|8160.0] "rpm" LPI + SG_ MAF : 40|8@1+ (5.447,0.0) [0.0|1388.985] "mg/TDC" LPI + SG_ TIA : 48|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" LPI + SG_ MAP m1 : 56|8@1+ (0.47058,0.0) [0.0|119.9979] "kPa" LPI + SG_ AMP m0 : 56|8@1+ (21.22,0.0) [0.0|5411.1] "hPa" LPI + +BO_ 128 EMS_DCT11: 8 EMS + SG_ PV_AV_CAN : 0|8@1+ (0.3906,0.0) [0.0|99.603] "%" TCU + SG_ TQ_STND : 8|6@1+ (10.0,0.0) [0.0|630.0] "Nm" TCU + SG_ F_N_ENG : 14|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ F_SUB_TQI : 15|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ N : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" TCU + SG_ TQI_ACOR : 32|8@1+ (0.390625,0.0) [0.0|99.6094] "%" IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0.0) [0.0|99.6094] "%" TCU + SG_ TQI : 48|8@1+ (0.390625,0.0) [0.0|99.609375] "%" TCU + SG_ CF_Ems_Alive : 56|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Ems_ChkSum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 1407 HU_MON_PE_01: 8 CLU + SG_ HU_Type : 0|8@1+ (1.0,0.0) [0.0|255.0] "" AVM,PGS + +BO_ 127 CGW5: 8 BCM + SG_ C_StopLampLhOpenSts : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_StopLampRhOpenSts : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HMSLOpenSts : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampLowLhOpenSts : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampLowRhOpenSts : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampHighLhOpenSts : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampHighRhOpenSts : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_DRLLampLhOpenSts : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_DRLLampRhOpenSts : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearFOGLhOpenSts : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearFOGRhOpenSts : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontFOGLhOpenSts : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontFOGRhOpenSts : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearEXTTailLhOpenSts : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearEXTTailRhOpenSts : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontEXTTailLhOpenSts : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontEXTTailRhOpenSts : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearTSIGLhOpenSts : 17|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearTSIGRhOpenSts : 18|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontTSIGLhOpenSts : 19|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontTSIGRhOpenSts : 20|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SBendingLhOpenSts : 21|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SBendingRhOpenSts : 22|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_LicensePlateLhOpenSts : 23|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_LicensePlateRhOpenSts : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1151 ESP11: 6 ESC + SG_ AVH_STAT : 0|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,TCU + SG_ LDM_STAT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" EPB,TCU + SG_ REQ_EPB_ACT : 3|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,TCU + SG_ REQ_EPB_STAT : 5|1@1+ (1.0,0.0) [0.0|1.0] "" EPB + SG_ ECD_ACT : 6|1@1+ (1.0,0.0) [0.0|1.0] "" EPB + SG_ _4WD_LIM_REQ : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS + SG_ ROL_CNT_ESP : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EPB,TCU + SG_ _4WD_TQC_LIM : 16|16@1+ (1.0,0.0) [0.0|65535.0] "Nm" _4WD,EMS + SG_ _4WD_CLU_LIM : 32|8@1+ (0.390625,0.0) [0.0|99.609375] "%" _4WD,EMS + SG_ _4WD_OPEN : 40|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,EMS + SG_ _4WD_LIM_MODE : 42|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD + +BO_ 1397 HU_AVM_E_00: 8 CLU + SG_ HU_AVM_Cal_Cmd : 0|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_Cal_Method : 4|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_Save_Controlpoint : 6|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_PT_X : 8|12@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_RearViewPointOpt : 20|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_PT_Y : 24|12@1+ (1.0,0.0) [0.0|4095.0] "" AVM,PGS + SG_ HU_AVM_FrontViewPointOpt : 36|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_SelectedMenu : 40|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,PGS + SG_ HU_AVM_CameraOff : 45|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_Option : 48|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_CrossLineMove_Cmd : 52|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_RearView_Option : 56|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_FrontView_Option : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + +BO_ 1395 HU_AVM_E_01: 8 CLU + SG_ HU_PGSSelectedMenu : 0|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_PGSOption : 8|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,PGS + SG_ HU_AVM_ParkingAssistMenu : 56|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_ParkingAssistSB : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + +BO_ 1393 OPI11: 5 OPI + SG_ CR_Opi_Spd_Rpm : 0|8@1+ (20.0,0.0) [0.0|3500.0] "rpm" TCU + SG_ CF_Opi_Over_Temp : 8|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Over_Cur : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Over_Vol : 10|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Hall_Fail : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Flt : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Motor_Dir : 15|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Romver : 16|8@1+ (1.0,0.0) [0.0|255.0] "" TCU + SG_ CF_Opi_PWM_Rate : 24|12@1+ (1.0,0.0) [0.0|100.0] "%" TCU + +BO_ 625 LPI11: 8 LPI + SG_ FUP_LPG_MMV : 0|8@1+ (128.0,0.0) [0.0|32640.0] "hPa" EMS + SG_ LV_FUEL_TYPE_BOX : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_BFS_IN_PROGRESS : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_GAS_OK : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_FUP_ENA_THD : 11|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,EMS,SMK + SG_ LPI_OBD : 12|4@1+ (1.0,0.0) [0.0|15.0] "" EMS + SG_ ERR_GAS : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ FAC_TI_GAS_COR : 24|16@1+ (3.05E-5,0.0) [0.0|1.9988175] "" EMS + SG_ FTL_AFU : 40|8@1+ (0.392,0.0) [0.0|99.96] "%" EMS + SG_ BFS_CYL : 48|8@1+ (1.0,0.0) [0.0|6.0] "Cyl Nr." EMS + SG_ LV_PRE_CDN_LEAK : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_CONF_INJECTION_DELAY : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_LPG_SW_DRIVER_REQ : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 356 VSM11: 4 ESC + SG_ CR_Esc_StrTqReq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" MDPS + SG_ CF_Esc_Act : 12|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,MDPS + SG_ CF_Esc_CtrMode : 13|3@1+ (1.0,0.0) [0.0|7.0] "" MDPS + SG_ CF_Esc_Def : 16|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Esc_AliveCnt : 17|4@1+ (1.0,0.0) [0.0|15.0] "" LDWS_LKAS,MDPS + SG_ CF_Esc_Chksum : 24|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,MDPS + +BO_ 1379 PGS_HU_PE_01: 8 PGS + SG_ PGS_State : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ PGS_ParkGuideState : 8|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ PGS_Option : 16|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ PGS_Version : 32|16@1+ (1.0,0.0) [0.0|65535.0] "" CLU + +BO_ 354 TCU_DCT13: 3 TCU + SG_ Clutch_Driving_Tq : 0|10@1+ (1.0,-512.0) [0.0|0.0] "Nm" ESC + SG_ Cluster_Engine_RPM : 10|13@1+ (0.9766,0.0) [0.0|0.0] "" CLU + SG_ Cluster_Engine_RPM_Flag : 23|1@1+ (1.0,0.0) [0.0|0.0] "" CLU + +BO_ 1378 HUD11: 4 HUD + SG_ CF_Hud_HeightStaus : 0|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ CF_Hud_PBackStatus : 6|2@1+ (1.0,0.0) [0.0|0.0] "" BCM,CLU + SG_ CF_Hud_Brightness : 8|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + +BO_ 608 EMS16: 8 EMS + SG_ TQI_MIN : 0|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ TQI : 8|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ TQI_TARGET : 16|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EPB,ESC,IBOX,TCU + SG_ GLOW_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,IBOX,SMK + SG_ CRUISE_LAMP_M : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ CRUISE_LAMP_S : 26|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ PRE_FUEL_CUT_IN : 27|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ENG_STAT : 28|3@1+ (1.0,0.0) [0.0|7.0] "" ABS,AHLS,AVM,BCM,CLU,EPB,ESC,EVP,FPCM,IBOX,LCA,LDWS_LKAS,MDPS,SCC,SMK,TCU + SG_ SOAK_TIME_ERROR : 31|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,EPB,IBOX,TCU + SG_ SOAK_TIME : 32|8@1+ (1.0,0.0) [0.0|255.0] "Min" _4WD,DATC,EPB,IBOX,TCU + SG_ TQI_MAX : 40|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ SPK_TIME_CUR : 48|8@1+ (0.375,-35.625) [-35.625|60.0] "" IBOX,TCU + SG_ Checksum : 56|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ AliveCounter : 60|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Ems_AclAct : 62|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,SCC + +BO_ 1371 AVM_HU_PE_00: 8 AVM + SG_ AVM_View : 0|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ AVM_ParkingAssist_BtnSts : 5|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ AVM_Display_Message : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ AVM_Popup_Msg : 16|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Ready : 20|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_ParkingAssist_Step : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_FrontBtn_Type : 28|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Option : 32|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_FrontViewPointOpt : 36|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_RearView_Option : 40|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_FrontView_Option : 44|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Version : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" CLU + +BO_ 1370 HU_AVM_PE_00: 8 CLU + SG_ HU_AVM_Status : 0|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + +BO_ 1369 CGW4: 8 BCM + SG_ CF_Gway_MemoryP1Cmd : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_MemoryP2Cmd : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackP1Cmd : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackP2Cmd : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_StrgWhlHeatedState : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackStopCmd : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,HUD + SG_ CF_Gway_StaticBendLhAct : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_StaticBendRhAct : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_DrvWdwStat : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RLWdwState : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RRWdwState : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_AstWdwStat : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_MemoryEnable : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBACKStopCmd : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBACKStop : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,HUD + SG_ CF_Gway_IMSBuzzer : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_DrvSeatBeltInd : 36|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_AstSeatBeltInd : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RCSeatBeltInd : 40|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RLSeatBeltInd : 42|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RRSeatBeltInd : 44|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RrWiperHighSw : 46|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RrWiperLowSw : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1367 EngFrzFrm12: 8 EMS + SG_ PID_06h : 0|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_07h : 8|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_08h : 16|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_09h : 24|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_0Bh : 32|8@1+ (1.0,0.0) [0.0|255.0] "kPa" AAF,IBOX,TCU + SG_ PID_23h : 40|16@1+ (10.0,0.0) [0.0|655350.0] "kPa" AAF,IBOX,TCU + +BO_ 1366 EngFrzFrm11: 8 EMS + SG_ PID_04h : 0|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" AAF,TCU + SG_ PID_05h : 8|8@1+ (1.0,-40.0) [-40.0|215.0] "deg" AAF,TCU + SG_ PID_0Ch : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" AAF,TCU + SG_ PID_0Dh : 32|8@1+ (1.0,0.0) [0.0|255.0] "km/h" AAF,TCU + SG_ PID_11h : 40|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" AAF,TCU + SG_ PID_03h : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" AAF,TCU + +BO_ 1365 FPCM11: 8 FPCM + SG_ CR_Fpcm_LPActPre : 0|8@1+ (3.137254902,0.0) [0.0|800.0] "kPa" EMS + SG_ CF_Fpcm_LPPumpOverCur : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrHi : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrDisc : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrShort : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LPPumpDiscShort : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LP_System_Error : 13|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrSigErr : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LPCtrCirFlt : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 852 LVR11: 7 LVR + SG_ CF_Lvr_GearInf : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,TCU + SG_ CF_Lvr_PRelStat : 4|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,SMK,TCU + SG_ CF_Lvr_BkeAct : 5|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Lvr_NFnStat : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Lvr_PosInf : 8|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_PosCpl : 12|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_UlkButStat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" TCU + SG_ CF_Lvr_PNStat : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lvr_ShtLkStat : 24|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_ShfErrInf : 28|20@1+ (1.0,0.0) [0.0|8191.0] "" CLU,TCU + SG_ CF_Lvr_AC : 48|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_CS : 52|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 1363 CGW2: 8 BCM + SG_ CF_Gway_GwayDiagState : 0|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_DDMDiagState : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SCMDiagState : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_PSMDiagState : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SJBDiagState : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IPMDiagState : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_LDMFail : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,LDWS_LKAS,LDWS_LKAS + SG_ CF_Gway_CLUSwGuiCtrl : 10|3@1+ (1.0,0.0) [0.0|63.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwGroup : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwMode : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwEnter : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_AutoLightValue : 16|1@1+ (1.0,0.0) [0.0|1.0] "" LCA,LCA + SG_ CF_Gway_BrakeFluidSw : 17|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_DrvSeatBeltInd : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_AvTail : 20|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,SNV,SNV + SG_ CF_Gway_RearFogAct : 21|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ExtTailAct : 22|1@1+ (1.0,0.0) [0.0|1.0] "" AVM,CLU,LCA,PGS,SPAS,AVM,LCA,PGS,SPAS + SG_ CF_Gway_RRDrSw : 23|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_RLDrSw : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IntTailAct : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CountryCfg : 26|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,Dummy + SG_ CF_Gway_WiperParkPosition : 32|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,EMS,LDWS_LKAS,AFLS,EMS,LDWS_LKAS + SG_ CF_Gway_HLLowLHFail : 33|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_HLLowRHFail : 34|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_ESCLFailWarn : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ESCLNotLockedWarn : 36|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ESCLNotUnlockWarn : 37|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IDoutWarn : 38|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ImmoLp : 40|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_BCMRKEID : 41|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_VehicleNotPWarn : 44|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_DeactivationWarn : 45|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_KeyBATDischargeWarn : 46|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SSBWarn : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SMKFobID : 48|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_SMKRKECmd : 51|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_AutoLightOption : 54|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_SJBDeliveryMode : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_KeyoutLp : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SMKDispWarn : 57|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,Dummy + SG_ CF_Gway_WngBuz : 61|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + +BO_ 339 TCS11: 8 ESC + SG_ TCS_REQ : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,TCU + SG_ MSR_C_REQ : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,EPB,SCC,TCU + SG_ TCS_PAS : 2|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,SCC,SPAS,TCU + SG_ TCS_GSC : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,TCU + SG_ CF_Esc_LimoInfo : 4|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,SCC + SG_ ABS_DIAG : 6|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB + SG_ ABS_DEF : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_DEF : 8|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_CTL : 9|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ ABS_ACT : 10|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ EBD_DEF : 11|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SPAS,TCU + SG_ ESP_PAS : 12|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,CLU,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_DEF : 13|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_CTL : 14|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ TCS_MFRN : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,EPB,TCU + SG_ DBC_CTL : 16|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ DBC_PAS : 17|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ DBC_DEF : 18|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ HAC_CTL : 19|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_PAS : 20|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_DEF : 21|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ ESS_STAT : 22|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,BCM,CLU,EMS,EPB + SG_ TQI_TCS : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_MSR : 32|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_SLW_TCS : 40|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ CF_Esc_BrkCtl : 48|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ BLA_CTL : 49|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CGW,CLU + SG_ AliveCounter_TCS1 : 52|4@1+ (1.0,0.0) [0.0|14.0] "" EMS,EPB,LDWS_LKAS + SG_ CheckSum_TCS1 : 56|8@1+ (1.0,0.0) [0.0|255.0] "" EMS,EPB,LDWS_LKAS + +BO_ 1362 SNV11: 4 SNV + SG_ CF_SNV_DisplayControl : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,HUD + SG_ CF_Snv_BeepWarning : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,HUD + SG_ CF_Snv_WarningMessage : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,HUD + SG_ CF_Snv_DetectionEnable : 7|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,HUD + SG_ CF_Snv_PedestrianDetect : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,HUD + SG_ CF_Snv_IRLampControl : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,HUD + +BO_ 593 MDPS12: 8 MDPS + SG_ CR_Mdps_StrColTq : 0|11@1+ (0.0078125,-8.0) [-8.0|7.9921875] "Nm" LDWS_LKAS + SG_ CF_Mdps_Def : 11|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_Mdps_ToiUnavail : 12|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_ToiActive : 13|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_ToiFlt : 14|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_FailStat : 15|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_MsgCount2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" ESC,LDWS_LKAS + SG_ CF_Mdps_Chksum2 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ESC,LDWS_LKAS + SG_ CF_Mdps_SErr : 37|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CR_Mdps_StrTq : 40|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" ESC + SG_ CR_Mdps_OutTq : 52|12@1+ (0.1,-204.8) [-204.8|204.7] "" ESC,LDWS_LKAS + +BO_ 1360 IAP11: 3 IAP + SG_ CF_Iap_EcoPmodSwi : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Iap_EcoPmodAct : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Iap_ReqWarn : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1356 TCU_DCT14: 8 TCU + SG_ Vehicle_Stop_Time : 0|5@1+ (1.0,0.0) [0.0|0.0] "" CLU + SG_ HILL_HOLD_WARNING : 5|1@1+ (1.0,0.0) [0.0|0.0] "" CLU + +BO_ 1353 BAT11: 8 EMS + SG_ BAT_SNSR_I : 0|16@1+ (0.01,-327.0) [-327.0|328.0] "A" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOC : 16|8@1+ (1.0,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_V : 24|14@1+ (0.0010,6.0) [6.0|18.0] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Temp : 38|9@1- (0.5,-40.0) [-40.0|125.0] "deg" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_State : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOH : 48|7@1+ (1.0,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Invalid : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOF : 56|7@1+ (0.1,0.0) [0.0|12.0] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Error : 63|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + +BO_ 1351 EMS15: 8 EMS + SG_ ECGPOvrd : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX,SCC + SG_ QECACC : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ ECFail : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ SwitchOffCondExt : 3|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ BLECFail : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ CF_Ems_IsaAct : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ FA_PV_CAN : 8|8@1+ (0.3906,0.0) [0.0|99.2] "%" IBOX,LDWS_LKAS,TCU + SG_ IntAirTemp : 16|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" _4WD,ECS,EPB,IBOX,TCU + SG_ STATE_DC_OBD : 24|7@1+ (1.0,0.0) [0.0|127.0] "" IBOX,TCU + SG_ INH_DC_OBD : 31|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ CTR_IG_CYC_OBD : 32|16@1+ (1.0,0.0) [0.0|65535.0] "" ACU,IBOX,TCU + SG_ CTR_CDN_OBD : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" IBOX,TCU + +BO_ 1350 DI_BOX12: 8 DI_BOX + SG_ CF_DiBox_FrtInjVDiagReg0 : 0|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg0 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg1 : 32|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg2 : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CR_DiBox_BatVol : 48|8@1+ (0.1,0.0) [0.0|25.5] "V" EMS + SG_ CF_DiBox_SedInjVChg : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_FrtInjVChg : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_SedInjVErrSPI : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_FrtInjVErrSPI : 59|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 1349 EMS14: 8 EMS + SG_ IMMO_LAMP_STAT : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ L_MIL : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,IBOX + SG_ IM_STAT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ AMP_CAN : 3|5@1+ (10.731613,458.98) [458.98|791.660003] "mmHg" CLU,IBOX,TCU,TPMS + SG_ BAT_Alt_FR_Duty : 8|8@1+ (0.4,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ VB : 24|8@1+ (0.1015625,0.0) [0.0|25.8984375] "V" CLU,CUBIS,DATC,EPB,FPCM,IBOX + SG_ EMS_VS : 32|12@1+ (0.0625,0.0) [0.0|255.875] "km/h" CLU + SG_ TEMP_FUEL : 56|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" FPCM + +BO_ 68 DATC11: 8 DATC + SG_ CF_Datc_Type : 0|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Datc_VerMaj : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Datc_VerMin : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CR_Datc_OutTempC : 24|8@1+ (0.5,-41.0) [-41.0|86.5] "deg" CLU,FPCM + SG_ CR_Datc_OutTempF : 32|8@1+ (1.0,-42.0) [-42.0|213.0] "deg" CLU + SG_ CF_Datc_IncarTemp : 40|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" BCM,CLU + +BO_ 67 DATC13: 8 DATC + SG_ CF_Datc_TempDispUnit : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ CF_Datc_ModDisp : 2|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_IonClean : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_ChgReqDisp : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_IntakeDisp : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AutoDisp : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_FrDefLed : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ CF_Datc_AutoDefogBlink : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_ClmScanDisp : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AqsDisp : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AcDisp : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_OpSts : 25|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Mtc_MaxAcDisp : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_DualDisp : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_PwrInf : 32|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_RearManual : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearAutoDisp : 40|2@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Datc_RearOffDisp : 42|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearClimateScnDisp : 44|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearChgReqDisp : 46|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearModDisp : 48|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_RearBlwDisp : 52|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_PSModDisp : 56|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_FrontBlwDisp : 60|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX + +BO_ 66 DATC12: 8 DATC + SG_ CR_Datc_DrTempDispC : 0|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU,IBOX + SG_ CR_Datc_DrTempDispF : 8|8@1+ (1.0,56.0) [58.0|90.0] "¢µ" CLU,IBOX + SG_ CR_Datc_PsTempDispC : 16|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU,IBOX + SG_ CR_Datc_PsTempDispF : 24|8@1+ (1.0,56.0) [58.0|90.0] "¢µ" CLU,IBOX + SG_ CR_Datc_RearDrTempDispC : 40|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU + SG_ CR_Datc_RearDrTempDispF : 48|8@1+ (1.0,58.0) [58.0|90.0] "¢µ" CLU + SG_ CF_Datc_CO2_Warning : 56|8@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1345 CGW1: 8 BCM + SG_ CF_Gway_IGNSw : 0|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC + SG_ CF_Gway_RKECmd : 3|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyLockSw : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyUnlockSw : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvDrSw : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU + SG_ CF_Gway_DrvSeatBeltSw : 10|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,ESC,IBOX,PSB,TCU,EMS,EPB,ESC,IBOX,PSB,TCU + SG_ CF_Gway_TrunkTgSw : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ECS,EMS,EPB,ESC,IBOX,ECS,EMS,EPB,ESC,IBOX + SG_ CF_Gway_AstSeatBeltSw : 14|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,PSB,IBOX,PSB + SG_ CF_Gway_SMKOption : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_HoodSw : 17|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,EPB,ESC,IBOX,EMS,EPB,ESC,IBOX + SG_ CF_Gway_TurnSigLh : 19|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + SG_ CF_Gway_WiperIntT : 21|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperIntSw : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperLowSw : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperHighSw : 26|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperAutoSw : 27|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_RainSnsState : 28|3@1+ (1.0,0.0) [0.0|7.0] "" AFLS,EMS,IBOX,LDWS_LKAS,AFLS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_HeadLampLow : 31|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,SNV,AFLS,EMS,IBOX,LDWS_LKAS,SNV + SG_ CF_Gway_HeadLampHigh : 32|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,AFLS,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_HazardSw : 33|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS,ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS + SG_ CF_Gway_AstDrSw : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,IBOX + SG_ CF_Gway_DefoggerRly : 36|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX,EMS,IBOX + SG_ CF_Gway_ALightStat : 37|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_LightSwState : 38|2@1+ (1.0,0.0) [0.0|3.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_Frt_Fog_Act : 40|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigRHSw : 41|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigLHSw : 42|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_DriveTypeOption : 43|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_StarterRlyState : 44|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_PassiveAccessLock : 45|2@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_WiperMistSw : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_PassiveAccessUnlock : 48|2@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_RrSunRoofOpenState : 50|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,DATC,IBOX + SG_ CF_Gway_PassingSW : 51|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_HBAControlMode : 52|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_HLpHighSw : 53|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_InhibitRMT : 54|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,MDPS,PGS,SCC,SPAS,TPMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,PGS,SCC,SPAS,TPMS + SG_ CF_Gway_RainSnsOption : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SunRoofOpenState : 57|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,DATC,IBOX,DATC,IBOX + SG_ CF_Gway_Ign1 : 58|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_Ign2 : 59|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_ParkBrakeSw : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IBOX,SCC,ESC,IBOX,SCC + SG_ CF_Gway_TurnSigRh : 62|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + +BO_ 64 DATC14: 8 DATC + SG_ CF_Datc_AqsLevelOut : 0|4@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_DiagMode : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CR_Datc_SelfDiagCode : 8|8@1+ (1.0,-1.0) [0.0|254.0] "" CLU + SG_ DATC_SyncDisp : 16|4@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_OffDisp : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_SmartVentDisp : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_SmartVentOnOffStatus : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_AutoDefogSysOff_Disp : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_ADSDisp : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 832 LKAS11: 8 LDWS_LKAS + SG_ CF_Lkas_LdwsSysState : 2|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX,PSB + SG_ CF_Lkas_SysWarning : 6|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Lkas_LdwsLHWarning : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,PSB + SG_ CF_Lkas_LdwsRHWarning : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,PSB + SG_ CF_Lkas_HbaLamp : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Lkas_FcwBasReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC + SG_ CR_Lkas_StrToqReq : 16|11@1+ (0.0078125,-8.0) [-8.0|8.0] "Nm" MDPS + SG_ CF_Lkas_ActToi : 27|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Lkas_ToiFlt : 28|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Lkas_HbaSysState : 29|3@1+ (1.0,0.0) [0.0|7.0] "" BCM,CLU + SG_ CF_Lkas_FcwOpt : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_HbaOpt : 34|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CGW + SG_ CF_Lkas_MsgCount : 36|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,MDPS + SG_ CF_Lkas_FcwSysState : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Lkas_FcwCollisionWarning : 43|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_FusionState : 45|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Lkas_Chksum : 48|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Lkas_FcwOpt_USM : 56|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Lkas_LdwsOpt_USM : 59|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,MDPS + +BO_ 1342 LKAS12: 6 LDWS_LKAS + SG_ CF_Lkas_TsrSlifOpt : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_LkasTsrStatus : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_TsrSpeed_Display_Clu : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_LkasTsrSpeed_Display_Navi : 24|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_Lkas_TsrAddinfo_Display : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1338 TMU_GW_E_01: 8 CLU + SG_ CF_Gway_TeleReqDrLock : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqDrUnlock : 2|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqHazard : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqHorn : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqEngineOperate : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1078 PAS11: 4 BCM + SG_ CF_Gway_PASDisplayFLH : 0|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayFRH : 3|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASRsound : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASDisplayFCTR : 8|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayRCTR : 11|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASFsound : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASDisplayRLH : 16|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASDisplayRRH : 19|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASCheckSound : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASSystemOn : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASOption : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PASDistance : 28|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 48 EMS18: 6 EMS + SG_ CF_Ems_DC1NumPerMSV : 0|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_DC2NumPerMSV : 8|16@1+ (1.0,0.0) [0.0|65535.0] "" DI_BOX + SG_ CR_Ems_DutyCyc1MSV : 24|8@1+ (0.1953,0.0) [0.0|49.8] "%" DI_BOX + SG_ CR_Ems_DutyCyc2MSV : 32|8@1+ (0.13725,0.0) [0.0|35.0] "%" DI_BOX + SG_ CR_Ems_DutyCyc3MSV : 40|8@1+ (0.392,0.0) [0.0|100.0] "%" DI_BOX + +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_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 + SG_ CF_Clu_HudBrightDnSW : 24|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudHeightUpSW : 26|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudHeightDnSW : 28|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudSet : 30|1@1+ (1.0,0.0) [0.0|1.0] "" HUD + SG_ CF_Clu_HudFontSizeSet : 31|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_LanguageInfo : 33|5@1+ (1.0,0.0) [0.0|31.0] "" BCM,PGS + SG_ CF_Clu_ClusterSound : 38|1@1- (1.0,0.0) [0.0|0.0] "" BCM,CGW,FATC + +BO_ 1066 _4WD13: 6 _4WD + SG_ _4WD_CURRENT : 0|8@1+ (0.390625,0.0) [-50.0|50.0] "A" TCU + SG_ _4WD_POSITION : 8|16@1+ (0.015625,0.0) [-180.0|180.0] "Deg" TCU + SG_ _4WD_CLU_THERM_STR : 24|8@1+ (1.0,0.0) [0.0|100.0] "%" TCU + SG_ _4WD_STATUS : 32|8@1+ (1.0,0.0) [0.0|15.0] "" ESC,TCU + +BO_ 1065 _4WD12: 8 _4WD + SG_ Ster_Pos : 0|16@1+ (1.0,-600.0) [-600.0|600.0] "Deg" ESC + SG_ FRSS : 16|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ FLSS : 24|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ RRSS : 32|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ RLSS : 40|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ CLU_PRES : 48|16@1+ (0.0625,-50.0) [-50.0|50.0] "Bar" ESC + +BO_ 809 EMS12: 8 EMS + SG_ CONF_TCU m1 : 0|6@1+ (1.0,0.0) [0.0|63.0] "" _4WD,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LCA,SMK + SG_ CAN_VERS m0 : 0|6@1+ (1.0,0.0) [0.0|7.7] "" _4WD,ABS,ESC,IBOX + SG_ TQ_STND m3 : 0|6@1+ (10.0,0.0) [0.0|630.0] "Nm" _4WD,DATC,ECS,EPB,ESC,FATC,IBOX + SG_ OBD_FRF_ACK m2 : 0|6@1+ (1.0,0.0) [0.0|63.0] "" _4WD,ESC,IBOX + SG_ MUL_CODE M : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ABS,ACU,BCM,CLU,DATC,ECS,EPB,ESC,IBOX,LCA,SMK,TCU + SG_ TEMP_ENG : 8|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" _4WD,BCM,CLU,DATC,EPB,ESC,IBOX,SMK,TCU + SG_ MAF_FAC_ALTI_MMV : 16|8@1+ (0.00781,0.0) [0.0|1.99155] "" IBOX,TCU + SG_ VB_OFF_ACT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ACK_ES : 25|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,IBOX + SG_ CONF_MIL_FMY : 26|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,IBOX,TCU + SG_ OD_OFF_REQ : 29|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ACC_ACT : 30|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ABS,CLU,ESC,IAP,IBOX,SCC,TCU + SG_ CLU_ACK : 31|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EPB,ESC,IBOX + SG_ BRAKE_ACT : 32|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ABS,ACU,AFLS,CLU,DATC,ECS,EPB,ESC,IBOX,LDWS_LKAS,TCU + SG_ ENG_CHR : 34|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,ABS,ACU,CLU,DATC,EPB,ESC,FATC,IBOX,SCC,SMK,TCU + SG_ GP_CTL : 38|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ TPS : 40|8@1+ (0.4694836,-15.0234742) [-15.0234742|104.6948357] "%" _4WD,ABS,ACU,CLU,DATC,ECS,EPB,ESC,IBOX,TCU + SG_ PV_AV_CAN : 48|8@1+ (0.3906,0.0) [0.0|99.603] "%" _4WD,AAF,ABS,ACU,AFLS,CLU,DATC,EPB,ESC,IAP,IBOX,LDWS_LKAS,SCC,TCU + SG_ ENG_VOL : 56|8@1+ (0.1,0.0) [0.0|25.5] "liter" _4WD,ABS,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,SCC,SMK + +BO_ 1064 _4WD11: 8 _4WD + SG_ _4WD_TYPE : 0|2@1+ (1.0,0.0) [0.0|3.0] "" ACU,ESC,TPMS + SG_ _4WD_SUPPORT : 2|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,ESC,TPMS + SG_ _4WD_ERR : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,ESC + SG_ CLU_DUTY : 16|8@1+ (1.0,0.0) [0.0|64.0] "%" ABS,ESC + SG_ R_TIRE : 24|8@1+ (1.0,200.0) [200.0|455.0] "mm" ABS,ESC,TPMS + SG_ _4WD_SW : 32|8@1+ (1.0,0.0) [0.0|9.9] "" ESC + SG_ _2H_ACT : 40|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC + SG_ _4H_ACT : 41|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,CLU,ESC,TPMS + SG_ LOW_ACT : 42|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,TCU,TPMS + SG_ AUTO_ACT : 43|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,TPMS + SG_ LOCK_ACT : 44|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,CLU,ESC,TPMS + SG_ _4WD_TQC_CUR : 48|16@1+ (1.0,0.0) [0.0|65535.0] "Nm" ABS,ESC + +BO_ 1319 HU_GW_E_01: 8 CLU + SG_ C_ADrLNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ C_ADrUNValueSet : 4|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ C_TwUnNValueSet : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_ABuzzerNValueSet : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_ArmWKeyNValueSet : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_PSMNValueSet : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SCMNValueSet : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_HLEscortNValueSet : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_WELNValueSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TriTurnLNValueSet : 22|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SNVWarnNValueSet : 24|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_LkasWarnNValueSet : 26|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1318 HU_GW_E_00: 8 CLU + SG_ C_ADrLURValueReq : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TwUnRValueReq : 2|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_AlarmRValueReq : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_IMSRValueReq : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_HLEscortRValueReq : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_WELRValueReq : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TriTurnLRValueReq : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SNVWarnRValueReq : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_LkasWarnRValueReq : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1317 GW_HU_E_01: 8 BCM + SG_ C_ADrLRValue : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_ADrURValue : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_TwUnRValue : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ABuzzerRValue : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ArmWKeyRValue : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_PSMRValue : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SCMRValue : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_HLEscortRValue : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_WELRValue : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TriTurnLRValue : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1316 GW_HU_E_00: 8 BCM + SG_ C_ADrLUNValueConf : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TwUnNValueConf : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_AlarmNValueConf : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_PSMNValueConf : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SCMNValueConf : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_HLEscortNValueConf : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_WELNValueConf : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TriTurnLNValueConf : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1315 GW_SWRC_PE: 8 BCM + SG_ C_ModeSW : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_MuteSW : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SeekDnSW : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SeekUpSW : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_BTPhoneCallSW : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_BTPhoneHangUpSW : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_DISCDownSW : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_DISCUpSW : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SdsSW : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_MTSSW : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_VolDnSW : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_VolUpSW : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1314 GW_IPM_PE_1: 8 BCM + SG_ C_AV_Tail : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ParkingBrakeSW : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_RKECMD : 4|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ C_BAState : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_IGNSW : 12|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_CountryCfg : 16|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_TailLampActivity : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ RearSW_RSELockOnOff : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SMKTeleCrankingState : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SMKTeleCrankingFailRes : 34|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1057 SCC12: 8 SCC + SG_ CF_VSM_Prefill : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_VSM_DecCmdAct : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_VSM_HBACmd : 2|2@1+ (1.0,0.0) [0.0|3.0] "" ESC + SG_ CF_VSM_Warn : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IAP + SG_ CF_VSM_Stat : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,PSB + SG_ CF_VSM_BeltCmd : 8|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,PSB + SG_ ACCFailInfo : 11|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,ESC,IBOX + SG_ ACCMode : 13|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IBOX,TCU + SG_ StopReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EPB,ESC + SG_ CR_VSM_DecCmd : 16|8@1+ (0.01,0.0) [0.0|2.55] "g" ESC + SG_ aReqMax : 24|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ TakeOverReq : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC,TCU + SG_ PreFill : 36|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,TCU + SG_ aReqMin : 37|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ CF_VSM_ConfMode : 48|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_Failinfo : 50|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_Status : 52|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_CmdAct : 54|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ AEB_StopReq : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC + SG_ CR_VSM_Alive : 56|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,PSB + SG_ CR_VSM_ChkSum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,PSB + +BO_ 1313 GW_DDM_PE: 8 BCM + SG_ C_DRVDoorStatus : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ASTDoorStatus : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_RLDoorStatus : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + 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.0) [0.0|1.0] "" CLU,EMS,ESC + SG_ SCCInfoDisplay : 1|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC + SG_ AliveCounterACC : 4|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,EMS,ESC,TCU + SG_ VSetDis : 8|8@1+ (1.0,0.0) [0.0|255.0] "km/h or MPH" CLU,ESC,TCU + SG_ ObjValid : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC,TCU + SG_ DriverAlertDisplay : 17|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ TauGapSet : 19|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC,TCU + SG_ ACC_ObjStatus : 22|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,ESC + SG_ ACC_ObjLatPos : 24|9@1+ (0.1,-20.0) [-20.0|31.1] "m" ABS,ESC + SG_ ACC_ObjDist : 33|11@1+ (0.1,0.0) [0.0|204.7] "m" ABS,ESC + SG_ ACC_ObjRelSpd : 44|12@1+ (0.1,-170.0) [-170.0|239.5] "m/s" ABS,ESC + SG_ Navi_SCC_Curve_Status : 56|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Curve_Act : 58|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Camera_Act : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Camera_Status : 62|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1312 CGW3: 8 BCM + SG_ CR_Photosensor_LH : 0|8@1+ (78.125,0.0) [0.0|20000.0] "" DATC,DATC + SG_ CR_Photosensor_RH : 10|8@1+ (78.125,0.0) [0.0|20000.0] "" DATC,DATC + SG_ CF_Hoodsw_memory : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EMS + SG_ C_MirOutTempSns : 24|8@1+ (0.5,-40.5) [-40.0|60.0] "deg" AAF,CLU,DATC,EMS,SPAS,AAF,DATC,EMS,SPAS + +BO_ 544 ESP12: 8 ESC + SG_ LAT_ACCEL : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_STAT : 11|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_DIAG : 12|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LONG_ACCEL : 13|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_DIAG : 25|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ CYL_PRES : 26|12@1+ (0.1,0.0) [0.0|409.5] "Bar" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRES_STAT : 38|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRESS_DIAG : 39|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EMS,EPB,IBOX,PSB,SCC,TCU + SG_ YAW_RATE : 40|13@1+ (0.01,-40.95) [-40.95|40.96] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_STAT : 53|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_DIAG : 54|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ ESP12_AliveCounter : 56|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ ESP12_Checksum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1307 CLU16: 8 CLU + SG_ CF_Clu_TirePressUnitNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" TPMS + SG_ CF_Clu_SlifNValueSet : 3|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_RearWiperNValueSet : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 790 EMS11: 8 EMS + SG_ SWI_IGK : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ABS,ACU,AHLS,CUBIS,DI_BOX,ECS,EPB,ESC,IBOX,LDWS_LKAS,MDPS,REA,SAS,SCC,TCU + SG_ F_N_ENG : 1|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,IBOX,MDPS,SCC,TCU + SG_ ACK_TCS : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ PUC_STAT : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,DATC,IBOX,TCU + SG_ TQ_COR_STAT : 4|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ESC,IBOX,TCU + SG_ RLY_AC : 6|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,IBOX,TCU + SG_ F_SUB_TQI : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQI_ACOR : 8|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ N : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,FPCM,IBOX,MDPS,SCC,TCU + SG_ TQI : 32|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ VS : 48|8@1+ (1.0,0.0) [0.0|254.0] "km/h" _4WD,AAF,ACU,AHLS,BCM,CLU,DATC,ECS,EPB,IBOX,LCA,LDWS_LKAS,LVR,MDPS,ODS,SCC,SMK,SPAS,TCU,TPMS + SG_ RATIO_TQI_BAS_MAX_STND : 56|8@1+ (0.0078,0.0) [0.0|2.0] "" _4WD,IBOX,TCU + +BO_ 1301 CLU14: 8 CLU + SG_ CF_Clu_ADrUNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_ADrLNValueSet : 3|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_EscortHLNValueSet : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_DoorLSNValueSet : 8|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_PSMNValueSet : 11|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_TTUnlockNValueSet : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_PTGMNValueSet : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_SCMNValueSet : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_WlightNValueSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_TempUnitNValueSet : 22|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,DATC + SG_ CF_Clu_MoodLpNValueSet : 24|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_TrfChgSet : 27|2@1+ (1.0,0.0) [0.0|3.0] "" AFLS + SG_ CF_Clu_OTTurnNValueSet : 29|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_LcaNValueSet : 32|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_RctaNValueSet : 34|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_RcwNValueSet : 36|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_EscOffNValueSet : 38|3@1+ (1.0,0.0) [0.0|7.0] "" ESC + SG_ CF_Clu_SccNaviCrvNValueSet : 41|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_SccNaviCamNValueSet : 43|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_SccAebNValueSet : 45|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_LkasModeNValueSet : 47|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_FcwNValueSet : 51|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_PasSpkrLvNValueSet : 53|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_SccDrvModeNValueSet : 56|3@1+ (1.0,0.0) [0.0|7.0] "" SCC + SG_ CF_Clu_HAnBNValueSet : 59|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_HfreeTrunkTgNValueSet : 61|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + +BO_ 275 TCU13: 8 TCU + SG_ N_TGT_LUP : 0|8@1+ (10.0,500.0) [500.0|3040.0] "rpm" EMS,IBOX + SG_ SLOPE_TCU : 8|6@1+ (0.5,-16.0) [-16.0|15.5] "%" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhCda : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_IsgInhib : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_BkeOnReq : 16|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_NCStat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_TarGr : 20|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,CLU,DATC,EMS,EPB,ESC,IBOX,SCC + SG_ CF_Tcu_ShfPatt : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhVis : 28|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_PRelReq : 29|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LVR + SG_ CF_Tcu_ITPhase : 30|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_ActEcoRdy : 31|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_TqGrdLim : 32|8@1+ (10.0,0.0) [0.0|2540.0] "Nm/s" EMS,IBOX + SG_ CR_Tcu_IsgTgtRPM : 40|8@1+ (20.0,0.0) [0.0|3500.0] "rpm" EMS,IBOX + SG_ CF_Tcu_SptRdy : 48|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Tcu_SbwPInfo : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_Alive3 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_ChkSum3 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + +BO_ 274 TCU12: 8 TCU + SG_ ETL_TCU : 0|8@1+ (2.0,0.0) [0.0|508.0] "Nm" EMS,IBOX + SG_ CUR_GR : 8|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,ESC,IBOX,SCC,TPMS + SG_ CF_Tcu_Alive : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX,SCC + SG_ CF_Tcu_ChkSum : 14|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX,SCC + SG_ VS_TCU : 16|8@1+ (1.0,0.0) [0.0|254.0] "km/h" BCM,CLU,DATC,EMS,IBOX,LCA,LVR,PGS,SMK,SNV + SG_ FUEL_CUT_TCU : 28|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ INH_FUEL_CUT : 29|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ IDLE_UP_TCU : 30|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ N_INC_TCU : 31|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15.0|15.0] "" EMS,IBOX + SG_ N_TC_RAW : 40|16@1+ (0.25,0.0) [0.0|16383.5] "rpm" EMS,IBOX + SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0.0) [0.0|0.9921875] "km/h" CLU,EMS,IBOX,LCA + +BO_ 273 TCU11: 8 TCU + SG_ TQI_TCU_INC : 0|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,ESC,IBOX + SG_ G_SEL_DISP : 8|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,AFLS,AVM,BCM,CGW,CLU,CUBIS,ECS,EMS,EPB,ESC,IAP,IBOX,LCA,LDWS_LKAS,LVR,MDPS,PGS,SCC,SMK,SNV,SPAS,TPMS + SG_ F_TCU : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX + SG_ TCU_TYPE : 14|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,EMS,ESC,IBOX + SG_ TCU_OBD : 16|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,ESC,IBOX + SG_ SWI_GS : 19|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,ESC,IBOX,SCC + SG_ GEAR_TYPE : 20|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,CLU,EMS,ESC,IBOX,SCC + SG_ TQI_TCU : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,ESC,IBOX + SG_ TEMP_AT : 32|8@1+ (1.0,-40.0) [-40.0|214.0] "deg" AAF,CLU,CUBIS,EMS,ESC,IBOX + SG_ N_TC : 40|16@1+ (0.25,0.0) [0.0|16383.5] "rpm" _4WD,EMS,EPB,ESC,IBOX + SG_ SWI_CC : 56|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,CLU,EMS,ESC,IBOX + SG_ CF_Tcu_Alive1 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_ChkSum1 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + +BO_ 16 ACU13: 8 ACU + SG_ CF_Acu_CshAct : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CUBIS,IBOX,ODS + +BO_ 1040 CGW_USM1: 8 BCM + SG_ CF_Gway_ATTurnRValue : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PTGMRValue : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_EscortHLRValue : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_TTUnlockRValue : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_ADrLRValue : 8|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_ADrURValue : 11|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_SCMRValue : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_WlightRValue : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PSMRValue : 18|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_OTTurnRValue : 21|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_DrLockSoundRValue : 24|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_HAnBRValue : 27|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_MoodLpRValue : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_HfreeTrunkRValue : 32|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_AutoLightRValue : 35|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_RearWiperRValue : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PasSpkrLvRValue : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + +BO_ 1292 CLU13: 8 CLU + SG_ CF_Clu_LowfuelWarn : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,FPCM,IBOX + SG_ CF_Clu_RefDetMod : 2|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX + SG_ CF_Clu_AvgFCU : 3|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ CF_Clu_AvsmCur : 5|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,SCC + SG_ CF_Clu_AvgFCI : 6|10@1+ (0.1,0.0) [0.0|102.2] "" IBOX + SG_ CF_Clu_DrivingModeSwi : 16|2@1+ (1.0,0.0) [0.0|3.0] "" DATC,ECS,EMS,ESC,IAP,MDPS,TCU + SG_ CF_Clu_FuelDispLvl : 18|5@1+ (1.0,0.0) [0.0|31.0] "" CGW,IBOX + SG_ CF_Clu_FlexSteerSW : 23|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Clu_DTE : 24|10@1+ (1.0,0.0) [0.0|1023.0] "" DATC + SG_ CF_Clu_TripUnit : 34|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ CF_Clu_SWL_Stat : 36|3@1+ (1.0,0.0) [0.0|7.0] "" ACU,EMS + SG_ CF_Clu_ActiveEcoSW : 39|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,EMS,TCU + SG_ CF_Clu_EcoDriveInf : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CUBIS,EMS,IAP,IBOX + SG_ CF_Clu_IsaMainSW : 43|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Clu_LdwsLkasSW : 56|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Clu_AltLStatus : 59|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,DATC,EMS + SG_ CF_Clu_AliveCnt2 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,LDWS_LKAS + +BO_ 1290 SCC13: 8 SCC + SG_ SCCDrvModeRValue : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ SCC_Equip : 3|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ AebDrvSetStatus : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC + +BO_ 1287 TCS15: 4 ESC + SG_ ABS_W_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,CUBIS,IBOX + SG_ TCS_OFF_LAMP : 1|2@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,CLU + SG_ TCS_LAMP : 3|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ACU,CLU,CUBIS,IBOX,SCC + SG_ DBC_W_LAMP : 5|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ DBC_F_LAMP : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,CLU + SG_ ESC_Off_Step : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ AVH_CLU : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,EPB + SG_ AVH_I_LAMP : 24|2@1+ (1.0,0.0) [0.0|3.0] "" EPB + SG_ EBD_W_LAMP : 26|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ AVH_ALARM : 27|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ AVH_LAMP : 29|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EPB,SPAS + +BO_ 1282 TCU14: 4 TCU + SG_ CF_TCU_WarnMsg : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_TCU_WarnImg : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_TCU_WarnSnd : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Tcu_GSel_BlinkReq : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,LVR + SG_ CF_Tcu_StRelStat : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn1 : 13|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn2 : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,ESC + +BO_ 1281 ECS11: 3 ECS + SG_ ECS_W_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,IBOX + SG_ SYS_NA : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ ECS_DEF : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ ECS_DIAG : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ L_CHG_NA : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Leveling_Off : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ LC_overheat : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Lifting : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Lowering : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Damping_Mode : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_Damping : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_Height : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_level : 16|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ ACT_Height : 20|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + +BO_ 1024 CLU_CFG11: 2 CLU + SG_ Vehicle_Type : 0|16@1+ (1.0,0.0) [0.0|65536.0] "" _4WD + +BO_ 1280 ACU14: 1 ACU + SG_ CF_SWL_Ind : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_TTL_Ind : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_SBR_Ind : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + +BO_ 512 EMS20: 6 EMS + SG_ FCO : 0|16@1+ (0.128,0.0) [0.0|8388.48] "ul" CLU,CUBIS,FPCM,IBOX + SG_ CF_Ems_PumpTPres : 16|8@1+ (3.137254902,0.0) [0.0|800.0] "kPa" FPCM,IBOX + SG_ Split_Stat : 32|1@1+ (1.0,0.0) [0.0|1.0] "" FPCM diff --git a/opendbc/hyundai_2015_mcan.dbc b/opendbc/hyundai_2015_mcan.dbc new file mode 100644 index 00000000000000..6bcd771e511205 --- /dev/null +++ b/opendbc/hyundai_2015_mcan.dbc @@ -0,0 +1,1564 @@ +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_: CLOCK HUD H_U DATC CCP KMA_TMU CUBIS TMU IPM RSE_R RRC CGW RSE_L AMP EDT SWRC IBOX CLU FHCU ASD MON AVM KBD + + +BO_ 3221225472 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX + SG_ C_WHEEL_FL : 0|12@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_WHEEL_FR : 0|12@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_WHEEL_RL : 0|12@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_WHEEL_RR : 0|12@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 2046 TP_EDT_AMP: 8 EDT + SG_ Byte0_TCP_7FE : 7|8@0+ (1,0) [0|0] "" AMP + SG_ Byte1_Data_7FE : 15|8@0+ (1,0) [0|0] "" AMP + SG_ Byte2_Data_7FE : 23|8@0+ (1,0) [0|0] "" AMP + SG_ Byte3_Data_7FE : 31|8@0+ (1,0) [0|0] "" AMP + SG_ Byte4_Data_7FE : 39|8@0+ (1,0) [0|0] "" AMP + SG_ Byte5_Data_7FE : 47|8@0+ (1,0) [0|0] "" AMP + SG_ Byte6_Data_7FE : 55|8@0+ (1,0) [0|0] "" AMP + SG_ Byte7_Data_7FE : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 251 HU_TMU_E_02: 8 H_U + SG_ HU_GPS_Year : 7|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Month : 15|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Day : 23|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Hour : 31|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Minute : 39|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Second : 47|8@0+ (1,0) [0|0] "" CUBIS,TMU + +BO_ 250 HU_TMU_E_01: 8 H_U + SG_ HU_VoiceRecCom : 2|3@0+ (1,0) [0|0] "" TMU + SG_ HU_LangChgCom : 5|3@0+ (1,0) [0|0] "" TMU + SG_ HU_CallEndCmd : 9|2@0+ (1,0) [0|0] "" TMU + SG_ HU_ServiceReqtID : 13|4@0+ (1,0) [0|0] "" TMU + SG_ HU_MicReqCmd : 15|2@0+ (1,0) [0|0] "" TMU + SG_ HU_SeviceAction : 18|3@0+ (1,0) [0|0] "" TMU + SG_ HU_eCallStatus : 20|2@0+ (1,0) [0|0] "" TMU + +BO_ 1269 TP_CLU_ANDAUTO_HU: 8 CLU + SG_ Byte0_TCP_4F5 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4F5 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4F5 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4F5 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4F5 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4F5 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4F5 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4F5 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1268 TP_HU_ANDAUTO_CLU: 8 H_U + SG_ Byte0_TCP_4F4 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4F4 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4F4 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4F4 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4F4 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4F4 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4F4 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4F4 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1267 TP_CLU_CARPLAY_HU: 8 CLU + SG_ Byte0_TCP_4F3 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4F3 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4F3 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4F3 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4F3 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4F3 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4F3 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4F3 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1266 TP_HU_CARPLAY_CLU: 8 H_U + SG_ Byte0_TCP_4F2 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4F2 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4F2 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4F2 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4F2 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4F2 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4F2 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4F2 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1263 TP_CLU_IBOX_HU: 8 CLU + SG_ Byte0_TCP_4EF : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4EF : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4EF : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4EF : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4EF : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4EF : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4EF : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4EF : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1262 TP_HU_IBOX_CLU: 8 H_U + SG_ Byte0_TCP_4EE : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4EE : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4EE : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4EE : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4EE : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4EE : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4EE : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4EE : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1261 TP_CLU_DLNA_HU: 8 CLU + SG_ Byte0_TCP_4ED : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4ED : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4ED : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4ED : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4ED : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4ED : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4ED : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4ED : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1260 TP_HU_DLNA_CLU: 8 H_U + SG_ Byte0_TCP_4EC : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4EC : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4EC : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4EC : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4EC : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4EC : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4EC : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4EC : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 491 GW_DDM_PE: 8 CLU + SG_ C_DRVDoorStatus : 1|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_ASTDoorStatus : 3|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_RLDoorStatus : 5|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_RRDoorStatus : 7|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_TrunkStatus : 9|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_OSMirrorStatus : 11|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + +BO_ 1259 TP_CLU_MP_HU: 8 CLU + SG_ Byte0_TCP_4EB : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4EB : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4EB : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4EB : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4EB : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4EB : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4EB : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4EB : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1258 TP_HU_MP_CLU: 8 H_U + SG_ Byte0_TCP_4EA : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4EA : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4EA : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4EA : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4EA : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4EA : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4EA : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4EA : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1257 TP_CLU_FM_HU: 8 CLU + SG_ Byte0_TCP_4E9 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E9 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E9 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E9 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E9 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E9 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E9 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E9 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1256 TP_HU_FM_CLU: 8 H_U + SG_ Byte0_TCP_4E8 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E8 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E8 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E8 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E8 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E8 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E8 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E8 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1255 TP_CLU_MLT_HU: 8 CLU + SG_ Byte0_TCP_4E7 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E7 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E7 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E7 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E7 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E7 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E7 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E7 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 487 HU_CLU_PE_13: 8 H_U + SG_ Navi_DistToPoint1_F : 11|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint1_I : 7|12@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint1_U : 23|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint2_I : 19|12@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint2_F : 35|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint2_U : 39|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint3_F : 51|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint3_I : 47|12@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint3_U : 63|4@0+ (1,0) [0|0] "" CLU,HUD + +BO_ 1254 TP_HU_MLT_CLU: 8 H_U + SG_ Byte0_TCP_4E6 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E6 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E6 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E6 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E6 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E6 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E6 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E6 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 486 HU_CLU_PE_12: 8 H_U + SG_ Navi_DistToDest_I : 7|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToDest_F : 19|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToDest_U : 23|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_EstimHour : 31|8@0+ (1,0) [0|254] "hh" CLU,HUD + SG_ Navi_EstimMin : 37|6@0+ (1,0) [0|59] "mm" CLU,HUD + SG_ Navi_EstimTimeType : 39|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_Compass : 45|6@0+ (7.5,-7.5) [0|352.5] "Degree" CLU,HUD + +BO_ 229 HU_SYS_E_00: 8 H_U + SG_ SYS_SW_Ver_Req : 1|2@0+ (1,0) [0|0] "" AMP,CCP,CGW,CLOCK,CLU,HUD,IBOX,RRC,RSE_L + SG_ SYS_CAN_Ver_Req : 3|2@0+ (1,0) [0|0] "" AMP,CCP,CGW,CLOCK,CLU,HUD,IBOX,RRC,RSE_L + SG_ SYS_HW_Ver_Req : 5|2@0+ (1,0) [0|0] "" AMP,CCP,CGW,CLOCK,CLU,IBOX,RRC + SG_ SYS_RBD_Req : 9|2@0+ (1,0) [0|0] "" AMP,IBOX + SG_ SYS_MOSTErrorDiag_Req : 11|2@0+ (1,0) [0|0] "" AMP,IBOX + SG_ SYS_Reset_Req : 17|2@0+ (1,0) [0|0] "" AMP,IBOX + +BO_ 1253 TP_CLU_VCDC_HU: 8 CLU + SG_ Byte0_TCP_4E5 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E5 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E5 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E5 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E5 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E5 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E5 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E5 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 485 HU_CLU_PE_11: 8 H_U + SG_ Navi_FixedSpdTrap : 3|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_MobileSpdTrap : 7|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_OverSpdAlarm : 11|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SpdRedlightTrap : 15|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_NonSpdTrap : 20|5@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_WarningZone : 27|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_MergeWarning : 33|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_CurveWarning : 39|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_BusSpdTrap : 43|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_SpdLimit_Type : 49|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_SpdLimit_Unit : 51|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_SpdInfo_Type : 55|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_SpdLimit : 63|8@0+ (1,0) [1|254] "" CLU,HUD + +BO_ 1252 TP_HU_VCDC_CLU: 8 H_U + SG_ Byte0_TCP_4E4 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E4 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E4 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E4 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E4 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E4 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E4 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E4 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1251 TP_CLU_JB_HU: 8 CLU + SG_ Byte0_TCP_4E3 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E3 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E3 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E3 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E3 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E3 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E3 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E3 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1250 TP_HU_JB_CLU: 8 H_U + SG_ Byte0_TCP_4E2 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E2 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E2 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E2 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E2 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E2 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E2 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E2 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1248 TP_TMU_HU: 8 TMU + SG_ Byte0_TCP_4E0 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E0 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E0 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E0 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E0 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E0 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E0 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E0 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 479 CLU_HU_PE_01: 8 CLU + SG_ CLU_Type : 7|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_Region : 15|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_VersionMinor : 23|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_VersionMajor : 31|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_CurrentDispState : 39|8@0+ (1,0) [0|0] "" H_U + SG_ C_DRVDRSW : 41|2@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_LowfuelWarning : 44|2@0+ (1,0) [0|0] "" H_U + SG_ CLU_PowerInfo : 46|2@0+ (1,0) [0|0] "" H_U + SG_ C_DrivingModeState : 50|3@0+ (1,0) [0|0] "" H_U + SG_ Clu_RheostatLvl : 55|5@0+ (1,0) [0|0] "" H_U,MON,SWRC + SG_ C_Clu_ActiveEcoSW : 57|2@0+ (1,0) [0|0] "" H_U + SG_ C_Detent : 59|2@0+ (1,0) [0|0] "" CCP,CLOCK,H_U,KBD,MON,RRC,RSE_L,RSE_R + SG_ C_DrivingModeOn : 61|2@0+ (1,0) [0|0] "" H_U + +BO_ 2015 TP_EDT_All_Req: 8 EDT + SG_ Byte0_TCP_7DF : 7|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte1_Data_7DF : 15|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte2_Data_7DF : 23|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte3_Data_7DF : 31|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte4_Data_7DF : 39|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte5_Data_7DF : 47|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte6_Data_7DF : 55|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte7_Data_7DF : 63|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + +BO_ 474 CLU_HU_PE_02: 8 CLU + SG_ CF_Clu_AvgFCU : 1|2@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_AvgFCL : 9|10@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_TermAvgSync : 25|2@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_EcoDriveInf : 36|3@0+ (1,0) [0|0] "" H_U + SG_ CR_Clu_TermAvgFCI : 33|10@0+ (1,0) [0|0] "" H_U + SG_ CF_CLU_EcoScore : 55|16@0+ (1,0) [0|0] "" H_U + +BO_ 1495 CLU_HU_P_05: 8 CLU + SG_ Clu_TripUnit : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ Clu_DTEWarn : 11|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ Clu_DTE : 7|12@0+ (1,0) [0|1500] "km" H_U,IBOX + SG_ Clu_AFC : 23|10@0+ (0.1,0) [0|99.9] "" H_U,IBOX + SG_ Clu_IFC : 29|10@0+ (0.1,0) [0|99.9] "" H_U,IBOX + SG_ Clu_Odometer : 47|24@0+ (1,0) [0|999999] "" H_U,IBOX + +BO_ 1494 CLU_HU_P_01: 8 CLU + SG_ CF_TripUnit : 13|2@0+ (1,0) [0|0] "" H_U + SG_ CF_DTE : 7|10@0+ (1,0) [0|0] "" H_U + +BO_ 214 AMP_HU_E_SYS: 8 AMP + SG_ AMP_SWVerMajor : 7|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_SWVerMinor : 15|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_CANVerMajor : 23|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_CANVerMinor : 31|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_RBDResult : 34|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_MOSTErrorDiagResult : 38|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_HWVerMajor : 55|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_HWVerMinor : 63|8@0+ (1,0) [0|254] "" H_U,IBOX + +BO_ 1492 CLU_HU_P_04: 8 CLU + SG_ MM_CR_Fatc_AcnComCst_W : 7|10@0+ (10,0) [0|8000] "W" H_U + SG_ MM_CR_Ldc_PwrMon_W : 12|8@0+ (10,0) [0|2550] "W" H_U + SG_ MM_CR_Fatc_PTCPwrCon_W : 17|10@0+ (10,0) [0|10000] "W" H_U + SG_ MM_CR_BmsChgExp_T_Fast : 39|16@0+ (1,0) [0|0] "minute" H_U + SG_ MM_CR_BmsChgExp_T_Slow : 55|16@0+ (1,0) [0|0] "minute" H_U + +BO_ 1491 CLU_HU_P_03: 8 CLU + SG_ MM_CF_Vcu_EvMod : 3|4@0+ (1,0) [0|0] "" H_U + SG_ MM_CF_Vcu_GarSelDisp : 7|4@0+ (999,0) [0|0] "" H_U + SG_ MM_CF_Vcu_ThiBatTir : 8|1@0+ (1,0) [0|0] "" H_U + SG_ CR_Mcu_MotEstTqPc : 23|10@0+ (0.2,-100) [-100|99.8] "%" H_U + SG_ CR_Mcu_MotActRotSpd_rpm : 39|16@0+ (1,-32768) [-32768|32767] "rpm" H_U + +BO_ 1490 CLU_HU_P_02: 8 CLU + SG_ MM_CR_Vcu_EcoSco : 3|4@0+ (1,0) [0|0] "" H_U + SG_ MM_CF_Vcu_PgmRun5 : 5|2@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Clu_Odometer_kph : 15|24@0+ (0.1,0) [0|0] "km" H_U + +BO_ 1489 DATC_P_B_01: 8 CLU + SG_ C_InhibitR_DATC : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_InhibitP_DATC : 50|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_InhibitN_DATC : 49|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_InhibitD_DATC : 48|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 465 CLU_HU_PE_03: 8 CLU + SG_ CF_Clu_EVDTEDisp : 0|9@0+ (1,0) [0|0] "" H_U,IBOX + SG_ CF_Clu_GasDTEDisp : 17|10@0+ (1,0) [0|0] "" H_U,IBOX + SG_ MM_CR_Clu_TotalDTEDisp : 34|11@0+ (1,0) [0|0] "" H_U,IBOX + SG_ CF_Clu_TripUnit : 49|2@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 1232 TP_HU_TMU: 8 H_U + SG_ Byte0_TCP_4D0 : 7|8@0+ (1,0) [0|0] "" TMU + SG_ Byte1_Data_4D0 : 15|8@0+ (1,0) [0|0] "" TMU + SG_ Byte2_Data_4D0 : 23|8@0+ (1,0) [0|0] "" TMU + SG_ Byte3_Data_4D0 : 31|8@0+ (1,0) [0|0] "" TMU + SG_ Byte4_Data_4D0 : 39|8@0+ (1,0) [0|0] "" TMU + SG_ Byte5_Data_4D0 : 47|8@0+ (1,0) [0|0] "" TMU + SG_ Byte6_Data_4D0 : 55|8@0+ (1,0) [0|0] "" TMU + SG_ Byte7_Data_4D0 : 63|8@0+ (1,0) [0|0] "" TMU + +BO_ 1488 CLU_HU_P_00: 8 CLU + SG_ MM_CR_Mcu_VehSpd_Kph : 7|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Mcu_VehSpdDec_Kph : 15|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Bms_Soc_Pc : 23|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Vcu_TqMotClu_Pc : 31|8@0+ (1,-127) [0|0] "" H_U + SG_ MM_CR_Bms_DrvEnaDist : 39|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Clu_Soc_Seg : 44|5@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 208 CLU_HU_E_SYS: 8 CLU + SG_ CLU_SWVerMajor : 7|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_SWVerMinor : 15|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_CANVerMajor : 23|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_CANVerMinor : 31|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_HWVerMajor : 55|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_HWVerMinor : 63|8@0+ (1,0) [0|254] "" H_U + +BO_ 448 HU_DATC_PE_00: 8 H_U + SG_ DATC_AqsLevelChg : 3|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ RSELockOnOff : 7|2@0+ (1,0) [0|0] "" CGW,DATC,IPM,RRC + SG_ DATC_AqsMode : 9|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_Graphreset_Info : 17|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_VRActivity : 33|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_PhoneActivity : 35|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ BlowerNoiseControl : 37|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + +BO_ 1211 TP_HU_TBT_CLU: 8 H_U + SG_ Byte0_TCP_4BB : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4BB : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4BB : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4BB : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4BB : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4BB : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4BB : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4BB : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1207 TP_HU_DAB_CLU: 8 H_U + SG_ Byte0_TCP_4B7 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4B7 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4B7 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4B7 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4B7 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4B7 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4B7 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4B7 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1206 TP_HU_XM_CLU: 8 H_U + SG_ Byte0_TCP_4B6 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4B6 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4B6 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4B6 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4B6 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4B6 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4B6 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4B6 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1204 TP_HU_DMB_CLU: 8 H_U + SG_ Byte0_TCP_4B4 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4B4 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4B4 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4B4 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4B4 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4B4 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4B4 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4B4 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 432 TMU_GW_PE_01: 8 TMU + SG_ C_DATCOnOffReq : 1|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ C_DATCTempUnit : 3|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ C_DATCTempSet : 15|8@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ TMU_IVRActivity : 33|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ TMU_PhoneActivity : 35|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + +BO_ 1195 TP_CLU_TBT_HU: 8 CLU + SG_ Byte0_TCP_4AB : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4AB : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4AB : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4AB : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4AB : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4AB : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4AB : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4AB : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1191 TP_CLU_DAB_HU: 8 CLU + SG_ Byte0_TCP_4A7 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4A7 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4A7 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4A7 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4A7 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4A7 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4A7 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4A7 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1190 TP_CLU_XM_HU: 8 CLU + SG_ Byte0_TCP_4A6 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4A6 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4A6 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4A6 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4A6 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4A6 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4A6 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4A6 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1188 TP_CLU_DMB_HU: 8 CLU + SG_ Byte0_TCP_4A4 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4A4 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4A4 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4A4 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4A4 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4A4 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4A4 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4A4 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1179 TP_HU_NAVI_CLU: 8 H_U + SG_ Byte0_TCP_49B : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_49B : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_49B : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_49B : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_49B : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_49B : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_49B : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_49B : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1178 TP_CLU_Ipod_HU: 8 CLU + SG_ Byte0_TCP_49A : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_49A : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_49A : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_49A : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_49A : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_49A : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_49A : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_49A : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 410 HU_CLU_PE_08: 8 H_U + SG_ VCDC_SelDiscNo : 11|4@0+ (1,0) [0|0] "" CLU + SG_ VCDC_TrackChapterNo : 7|10@0+ (1,0) [0|0] "" CLU + SG_ VCDC_PlayTime : 23|24@0+ (1,0) [0|0] "" CLU + SG_ MLT_PlayTime : 47|24@0+ (1,0) [0|0] "" CLU + +BO_ 1176 TP_CLU_DVD_HU: 8 CLU + SG_ Byte0_TCP_498 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_498 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_498 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_498 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_498 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_498 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_498 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_498 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1175 TP_CLU_USB_HU: 8 CLU + SG_ Byte0_TCP_497 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_497 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_497 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_497 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_497 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_497 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_497 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_497 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 407 HU_CLU_PE_05: 8 H_U + SG_ HU_LanguageInfo : 7|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_MuteStatus : 9|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_VolumeStatus : 15|6@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_NaviDisp : 17|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_NaviStatus : 19|2@0+ (1,0) [0|0] "" CGW,CLU,HUD,IPM + SG_ HU_DistanceUnit : 21|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_Navigation_On_Off : 23|2@0+ (1,0) [0|0] "" AVM,CGW,CLU,DATC,HUD,IPM + +BO_ 1942 TP_AMP_HU_DiagRes: 8 AMP + SG_ Byte0_TCP_796 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_796 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_796 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_796 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_796 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_796 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_796 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_796 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 406 HU_CLU_PE_04: 8 H_U + SG_ C_SDARS_ChannelNo : 7|8@0+ (1,0) [0|0] "" CLU + SG_ C_NaviRouteGuidance : 11|2@0+ (1,0) [0|0] "" CLU + SG_ HD_SPS_ChannelNo : 15|4@0+ (1,0) [0|0] "" CLU + SG_ C_SDARS_PresetNo : 19|4@0+ (1,0) [0|0] "" CLU + SG_ DAB_ServiceFollowing : 21|2@0+ (1,0) [0|0] "" CLU + SG_ SXM_ChannelNo : 25|10@0+ (1,0) [0|999] "" AMP,CLU,HUD + +BO_ 1941 TP_HU_AMP_DiagReq: 8 H_U + SG_ Byte0_TCP_795 : 7|8@0+ (1,0) [0|0] "" AMP + SG_ Byte1_Data_795 : 15|8@0+ (1,0) [0|0] "" AMP + SG_ Byte2_Data_795 : 23|8@0+ (1,0) [0|0] "" AMP + SG_ Byte3_Data_795 : 31|8@0+ (1,0) [0|0] "" AMP + SG_ Byte4_Data_795 : 39|8@0+ (1,0) [0|0] "" AMP + SG_ Byte5_Data_795 : 47|8@0+ (1,0) [0|0] "" AMP + SG_ Byte6_Data_795 : 55|8@0+ (1,0) [0|0] "" AMP + SG_ Byte7_Data_795 : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 1173 TP_CLU_CD_HU: 8 CLU + SG_ Byte0_TCP_495 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_495 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_495 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_495 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_495 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_495 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_495 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_495 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 405 HU_CLU_PE_03: 8 H_U + SG_ HU_IntegPresetNum : 7|8@0+ (1,0) [0|0] "" AMP,CLU,HUD + SG_ Radio_Area : 10|8@0+ (1,0) [0|0] "" CLU + SG_ DMB_PresetNo : 29|5@0+ (1,0) [0|0] "" CLU + SG_ RADIO_PresetNo : 18|5@0+ (1,0) [0|0] "" CLU + SG_ HU_Opstate_DIS2 : 38|7@0+ (1,0) [0|0] "" AMP,CLU,HUD + +BO_ 1168 TP_HU_USB_CLU: 8 H_U + SG_ Byte0_TCP_490 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_490 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_490 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_490 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_490 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_490 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_490 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_490 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1936 TP_HU_All_Req: 8 H_U + SG_ Byte0_TCP_790 : 7|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte1_Data_790 : 15|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte2_Data_790 : 23|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte3_Data_790 : 31|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte4_Data_790 : 39|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte5_Data_790 : 47|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte6_Data_790 : 55|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte7_Data_790 : 63|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + +BO_ 1167 TP_HU_Ipod_CLU: 8 H_U + SG_ Byte0_TCP_48F : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_48F : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_48F : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_48F : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_48F : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_48F : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_48F : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_48F : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1166 TP_HU_DVD_CLU: 8 H_U + SG_ Byte0_TCP_48E : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_48E : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_48E : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_48E : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_48E : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_48E : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_48E : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_48E : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1165 TP_HU_CD_CLU: 8 H_U + SG_ Byte0_TCP_48D : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_48D : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_48D : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_48D : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_48D : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_48D : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_48D : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_48D : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1164 TP_CLU_NAVI_HU: 8 CLU + SG_ Byte0_TCP_48C : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_48C : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_48C : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_48C : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_48C : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_48C : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_48C : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_48C : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 139 AMP_HU_E_12: 8 AMP + SG_ AMP_Beep2VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2FrequencyState : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2OutputMaskState : 31|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 138 AMP_HU_E_11: 8 AMP + SG_ AMP_Beep1VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1FrequencyState : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1OutputMaskState : 31|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 137 AMP_HU_E_10: 8 AMP + SG_ AMP_MTSOutputMaskSupport : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSMuteMaskSupport : 5|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFOutputMaskSupport : 9|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFMuteMaskSupport : 13|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviOutputMaskSupport : 17|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviMuteMaskSupport : 21|2@0+ (1,0) [0|0] "" H_U + +BO_ 1928 TP_HU_PhyRes: 8 H_U + SG_ Byte0_TCP_788 : 7|8@0+ (1,0) [0|0] "" EDT + SG_ Byte1_Data_788 : 15|8@0+ (1,0) [0|0] "" EDT + SG_ Byte2_Data_788 : 23|8@0+ (1,0) [0|0] "" EDT + SG_ Byte3_Data_788 : 31|8@0+ (1,0) [0|0] "" EDT + SG_ Byte4_Data_788 : 39|8@0+ (1,0) [0|0] "" EDT + SG_ Byte5_Data_788 : 47|8@0+ (1,0) [0|0] "" EDT + SG_ Byte6_Data_788 : 55|8@0+ (1,0) [0|0] "" EDT + SG_ Byte7_Data_788 : 63|8@0+ (1,0) [0|0] "" EDT + +BO_ 136 AMP_HU_E_09: 8 AMP + SG_ AMP_MaxBeep2VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2Freq_State : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2OutputMaskSup : 33|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 135 AMP_HU_E_08: 8 AMP + SG_ AMP_MaxBeep1VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1Freq_State : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1OutputMaskSup : 33|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 134 AMP_HU_E_07: 8 AMP + SG_ ASD_SetValue : 2|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ ASD_Version : 15|8@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 1157 TP_HU_CLU_HF: 8 H_U + SG_ Byte0_TCP_485 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_485 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_485 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_485 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_485 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_485 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_485 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_485 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 133 AMP_HU_E_06: 8 AMP + SG_ AMP_MaxVolumeStep : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBalanceStep : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxFadeStep : 23|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBassStep : 31|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxMidStep : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxTrebleStep : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_ASDMajorVer : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_ASDMinorVer : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 389 AMP_HU_PE_05: 8 AMP + SG_ AMP_EngOrderC2Setting : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_EngOrderC4Setting : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_EngOrderC6Setting : 23|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand0Setting : 31|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand1Setting : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand2Setting : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand3Setting : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand4Setting : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 132 AMP_HU_E_05: 8 AMP + SG_ AMP_HFVolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFAudioCutState : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFOutputMaskState : 23|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFMuteMaskState : 39|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxHFVolumeState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxHFAudioCutState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 388 AMP_HU_PE_04: 8 AMP + SG_ AMP_PESSModeState : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_PESSDesignSetting : 4|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_PESSAPSSetting : 7|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_PESSVolumeSetting : 15|8@0+ (1,0) [0|0] "" H_U + +BO_ 1156 TP_CLU_HF_HU: 8 CLU + SG_ Byte0_TCP_484 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_484 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_484 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_484 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_484 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_484 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_484 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_484 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 131 AMP_HU_E_04: 8 AMP + SG_ AMP_MTSVolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSAudioCutState : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSOutputMaskState : 23|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSMuteMaskState : 39|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxMTSVolumeState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxMTSAudioCutState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 387 AMP_HU_PE_03: 8 AMP + SG_ AMP_MainVolumeSetting : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_BalanceSetting : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_FadeSetting : 23|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_BassSetting : 31|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MidSetting : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_TrebleSetting : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_VehicleSpeedamp : 55|8@0+ (1,0) [0|0] "" H_U + +BO_ 130 AMP_HU_E_03: 8 AMP + SG_ AMP_NaviVolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviAudioCutState : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviOutputMaskState : 23|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviMuteMaskState : 39|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxNaviVolumeState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxNaviAudioCutState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 129 AMP_HU_E_02: 8 AMP + SG_ AMP_DriveState : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_ConvertibleTopState : 5|2@0+ (1,0) [0|0] "" H_U + +BO_ 385 AMP_HU_PE_02: 8 AMP + SG_ AMP_MuteState : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_RearSpMuteState : 3|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SurroundModeState : 9|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_EQState : 13|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SPDIFMuteSt : 17|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_BeatsModeState : 21|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_DefaultBeep1St : 25|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_DefaultBeep2St : 29|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_AudioSource : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_VIPModeState : 41|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_QLSModeState : 43|2@0+ (1,0) [0|0] "" H_U + +BO_ 128 AMP_HU_E_01: 8 AMP + SG_ AMP_CurrentVehicleID : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_SPDIFModeState : 11|4@0+ (1,0) [0|0] "" H_U + SG_ AMP_MajorVer : 23|8@0+ (1,0) [0|0] "" H_U,MON + SG_ AMP_MinorVer : 31|8@0+ (1,0) [0|0] "" H_U,MON + SG_ AMP_UpdateStartResp : 33|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_UpdateEndResp : 41|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_TuningMajorVer : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_TuningMinorVer : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 384 AMP_HU_PE_01: 8 AMP + SG_ AMP_HFModeState : 1|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ HU_InitInfo : 3|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_ASDModeState : 6|3@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_NaviModeState : 9|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_SPDIFInfo : 12|3@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_MTSModeState : 17|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_VSCModeState : 25|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_SDVCStepState : 29|3@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_Beep1ModeState : 33|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_Beep2ModeState : 41|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_DistrInfoState : 55|8@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_INFORM_TO_IPM : 57|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ AMP_SignalDoctorState : 59|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_AutoVolumeState : 61|2@0+ (1,0) [0|0] "" H_U + +BO_ 1408 AMP_HU_P_01: 8 AMP + SG_ AMP_SupportMute : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportHFMode : 3|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportCfgBeep1 : 5|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportCfgBeep2 : 7|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSpeedAdjust : 9|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSurroundMode : 11|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportNaviMode : 13|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportMTSMode : 15|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportTopState : 17|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportBothLHDandRHD : 19|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportEQState : 21|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportVehicleID : 23|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportAudioSource : 25|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSPDIFModeState : 27|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportRearSpMute : 29|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportVEQMode : 31|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MakerID : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportASDMode : 41|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportBeatsMode : 43|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportVIPMode : 45|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportQLS : 47|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSignalDoctor : 49|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportAutoVolume : 51|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportPESSMode : 53|2@0+ (1,0) [0|0] "" H_U + +BO_ 1920 TP_HU_PhyReq: 8 EDT + SG_ Byte0_TCP_780 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_780 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_780 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_780 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_780 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_780 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_780 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_780 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 371 HU_TMU_PE_01: 8 H_U + SG_ HU_AliveStatus : 1|2@0+ (1,0) [0|0] "" CLU,CGW,TMU + SG_ HU_DeviceType : 5|4@0+ (1,0) [0|0] "" TMU + SG_ HU_DistanceUnit : 7|2@0+ (1,0) [0|0] "" TMU + SG_ HU_AudAllocStatus : 9|2@0+ (1,0) [0|0] "" TMU + SG_ HU_PowerStatus : 12|3@0+ (1,0) [0|0] "" TMU + SG_ HU_BTCallStatus : 15|3@0+ (1,0) [0|0] "" TMU + SG_ HU_VoiceRecStatus : 17|2@0+ (1,0) [0|0] "" TMU + SG_ HU_LangStatus : 20|3@0+ (1,0) [0|0] "" TMU + +BO_ 369 HU_Car_PE_01: 8 H_U + SG_ HU_VehiclePwr : 3|4@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CLOCK,CLU,CUBIS,DATC,FHCU,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + +BO_ 1392 HU_TMU_P_01: 8 H_U + SG_ HU_GPS_Signal : 7|64@0+ (1,0) [0|0] "" TMU + +BO_ 112 HU_AMP_E_09: 8 H_U + SG_ AMP_Beep1VolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1Frequency : 15|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1Ch_OutputMask : 31|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1DurationOn : 47|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1DurationOff : 55|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1NumberOfCycles : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 1390 GW_CLU_P: 8 CLU + SG_ C_VehicleSpeed : 7|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ C_Odometer : 15|24@0+ (1,0) [0|999999] "" H_U,IBOX + +BO_ 363 GW_IPM_PE_2: 8 CLU + SG_ C_DRVUnlockState : 1|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_ASTUnlockState : 3|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_RLUnlockstate : 5|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_RRUnlockState : 7|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_VehicleInfoTMU : 9|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_Engine_Status : 11|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_TMULockFeedBack : 23|2@0+ (1,0) [0|0] "" CUBIS,TMU + +BO_ 362 GW_IPM_PE_1: 8 CLU + SG_ C_AV_Tail : 1|2@0+ (1,0) [0|0] "" AMP,CCP,CLOCK,CLU,HUD,H_U,IBOX,RRC,RSE_L + SG_ C_ParkingBrakeSW : 3|2@0+ (1,0) [0|0] "" H_U + SG_ C_RKECMD : 7|4@0+ (1,0) [0|0] "" H_U + SG_ C_BAState : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_IGNSW : 14|3@0+ (1,0) [0|0] "" AMP,AVM,CUBIS,EDT,H_U,MON,RRC,SWRC + SG_ C_CountryCfg : 18|3@0+ (1,0) [0|0] "" AVM,H_U + SG_ C_AltL : 25|2@0+ (1,0) [0|0] "" H_U + SG_ C_TailLampActivity : 27|2@0+ (1,0) [0|0] "" AMP,CCP,CLOCK,HUD,H_U,IBOX,RRC,RSE_L,SWRC + SG_ RearSW_RSELockOnOff : 29|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_TMULockFeedBack : 31|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_SMKTeleCrankingState : 33|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_SMKTeleCrankingFailRes : 35|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_RKECMD_GEN2 : 39|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_Acu_CshAct : 41|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_IntTailAct : 43|2@0+ (1,0) [0|0] "" AMP,CCP,CLOCK,CLU,HUD,H_U,IBOX,RRC,RSE_L + SG_ C_PassiveAccessUnlock : 47|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ Lca_IndLeft : 49|2@0+ (1,0) [0|0] "" H_U + SG_ FL_SndWarn : 51|2@0+ (1,0) [0|0] "" AMP + SG_ FR_SndWarn : 53|2@0+ (1,0) [0|0] "" AMP + SG_ Lca_IndRight : 55|2@0+ (1,0) [0|0] "" H_U + SG_ RCTA_IndLeft : 57|2@0+ (1,0) [0|0] "" H_U + SG_ RL_SndWarn : 59|2@0+ (1,0) [0|0] "" AMP + SG_ RR_SndWarn : 61|2@0+ (1,0) [0|0] "" AMP + SG_ RCTA_IndRight : 63|2@0+ (1,0) [0|0] "" H_U + +BO_ 361 GW_CHASSIS_PE_1: 8 CLU + SG_ C_Inhibit_State : 3|4@0+ (1,0) [0|0] "" AVM,H_U + SG_ C_P_BrakeStatus : 5|2@0+ (1,0) [0|0] "" AVM,H_U + SG_ C_Clu_AltLStatus : 7|2@0+ (1,0) [0|0] "" AVM,H_U + +BO_ 359 GW_WARNING_PE_01: 8 CLU + SG_ Spas_BEEP_Alarm : 3|4@0+ (1,0) [0|0] "" AMP + SG_ Spas_Audio_VolumeDown : 5|2@0+ (1,0) [0|0] "" AMP + SG_ Spas_Spkr_Flh_Alarm : 9|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Fcnt_Alarm : 11|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Frh_Alarm : 13|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Rlh_Alarm : 17|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Rcnt_Alarm : 19|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Rrh_Alarm : 21|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Lkas_SysStatus : 27|4@0+ (1,0) [0|0] "" AMP,H_U + SG_ Lkas_LH_Warning : 29|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Lkas_RH_Warning : 31|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Level : 35|3@0+ (1,0) [0|0] "" AMP + SG_ Lkas_Audio_VolumeDown : 37|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Audio_VolumeDown : 39|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_BEEP_Alarm : 43|4@0+ (1,0) [0|0] "" AMP + SG_ Pas_Audio_VolumeDown : 45|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Level : 32|3@0+ (1,0) [0|0] "" AMP + SG_ Pas_Spkr_Flh_Alarm : 49|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Fcnt_Alarm : 51|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Frh_Alarm : 53|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Rlh_Alarm : 57|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Rcnt_Alarm : 59|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Rrh_Alarm : 61|2@0+ (1,0) [0|0] "" AMP,H_U + +BO_ 1376 HU_TMU_P_02: 8 H_U + SG_ HU_GPS_Signal2 : 7|8@0+ (2,0) [0|0] "Degree" TMU + SG_ HU_GPS_Signal3 : 9|2@0+ (1,0) [0|0] "" TMU + SG_ HU_GPS_Signal4 : 12|3@0+ (1,0) [0|0] "" TMU + +BO_ 93 DATC_HU_E_SYS: 8 CLU + SG_ DATC_SWVerMajor : 7|8@0+ (1,0) [0|254] "" H_U + SG_ DATC_SWVerMinor : 15|8@0+ (1,0) [0|254] "" H_U + SG_ DATC_CANVerMajor : 23|8@0+ (1,0) [0|254] "" H_U + SG_ DATC_CANVerMinor : 31|8@0+ (1,0) [0|254] "" H_U + +BO_ 344 GW_CLU_PE: 8 CLU + SG_ C_InhibitP : 1|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitR : 3|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitN : 5|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitD : 7|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_P_BrakeStatus : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_Clu_AltLStatus : 11|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ CF_Clu_LowfuelWarning : 13|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitRMT : 15|2@0+ (1,0) [0|0] "" H_U + SG_ CF_SMKRKECmd : 18|3@0+ (1,0) [0|0] "" H_U + +BO_ 87 HU_E_02: 8 H_U + SG_ NaviValidity : 1|2@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 343 GW_WARNING_PE_02: 8 CLU + SG_ CF_Lkas_TsrSlifOpt : 1|2@0+ (1,0) [0|3] "" H_U + SG_ CF_Lkas_TsrStatus : 3|2@0+ (1,0) [0|3] "" H_U + SG_ CF_Lkas_TsrAddinfo_Disp : 7|2@0+ (1,0) [0|3] "" H_U + SG_ CF_Lkas_TsrSpeed_Display : 15|8@0+ (1,0) [0|255] "" H_U + +BO_ 75 HU_AMP_E_12: 8 H_U + SG_ AMP_EngOrderC2GainSet : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_EngOrderC4GainSet : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_EngOrderC6GainSet : 23|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand0GainSet : 31|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand1GainSet : 39|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand2GainSet : 47|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand3GainSet : 55|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand4GainSet : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 74 HU_AMP_E_11: 8 H_U + SG_ AMP_PESSMode : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_PESSDesignSet : 4|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_PESSAPSSet : 7|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_PESSVolumeSet : 15|8@0+ (1,0) [0|0] "" AMP + +BO_ 1864 TP_AMP_EDT: 8 AMP + SG_ Byte0_TCP_748 : 7|8@0+ (1,0) [0|0] "" EDT + SG_ Byte1_Data_748 : 15|8@0+ (1,0) [0|0] "" EDT + SG_ Byte2_Data_748 : 23|8@0+ (1,0) [0|0] "" EDT + SG_ Byte3_Data_748 : 31|8@0+ (1,0) [0|0] "" EDT + SG_ Byte4_Data_748 : 39|8@0+ (1,0) [0|0] "" EDT + SG_ Byte5_Data_748 : 47|8@0+ (1,0) [0|0] "" EDT + SG_ Byte6_Data_748 : 55|8@0+ (1,0) [0|0] "" EDT + SG_ Byte7_Data_748 : 63|8@0+ (1,0) [0|0] "" EDT + +BO_ 327 TMU_HU_PE_03: 8 TMU + SG_ TMU_TbT_TurnIcon : 7|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_CountDownBar : 11|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_Distance_Unit : 13|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DestDistance_Unit : 15|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DistanceLo : 27|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DistanceHi : 23|12@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DestDistanceLo : 43|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DestDistanceHi : 39|12@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_ExpectRemainHour : 55|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_ExpectRemainMin : 61|6@0+ (1,0) [0|0] "" H_U + +BO_ 326 TMU_HU_PE_02: 8 TMU + SG_ TMU_CallStatus : 3|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_CallType : 6|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_CDMA_Streng : 11|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_PacketStatus : 13|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_TalkTimeHour : 20|5@0+ (1,0) [0|0] "" H_U + SG_ TMU_TalkTimeMinute : 29|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_TalkTimeSecond : 37|6@0+ (1,0) [0|0] "" H_U + +BO_ 325 TMU_HU_PE_01: 8 TMU + SG_ TMU_AliveStatus : 2|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_AudioStatus : 4|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_UpdateStatus : 7|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_LangStatus : 10|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_VoiceRecStatus : 12|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_MicStatus : 14|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_ServCommuStatus : 19|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_PowerStatus : 21|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_EngineStatus : 23|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_DownProgress : 31|8@0+ (1,0) [0|0] "" H_U + +BO_ 69 TMU_HU_E_04: 8 TMU + SG_ TMU_eCall : 1|2@0+ (1,0) [0|0] "" H_U + +BO_ 67 TMU_GW_E_01: 8 TMU + SG_ C_ReqDrLock : 1|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqDrUnlock : 3|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqHazard : 5|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqHorn : 7|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqEngineOperate : 9|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + +BO_ 66 TMU_HU_E_03: 8 TMU + SG_ CDMA_SelfDiag : 1|2@0+ (1,0) [0|0] "" H_U + SG_ CDMA_Antena_SelfDiag : 3|2@0+ (1,0) [0|0] "" H_U + +BO_ 1345 TMU_HU_P_02: 8 TMU + SG_ TMU_SupVoiceTextService : 1|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_SupEcoCoachService : 3|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_SupSongTagService : 5|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_SupContentService : 7|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_MajorVersion : 15|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_MinorVersion : 23|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_DistributeInfo : 27|4@0+ (1,0) [0|0] "" H_U + +BO_ 65 TMU_HU_E_02: 8 TMU + SG_ TMU_BarLevel1 : 7|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel2 : 1|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel4 : 21|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel3 : 11|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel5 : 31|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel6 : 25|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel8 : 45|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel7 : 35|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel9 : 55|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel10 : 63|6@0+ (1,0) [0|0] "" H_U + +BO_ 1344 TMU_HU_P_01: 8 TMU + SG_ TMU_Arrow : 3|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_ReFill_Info : 5|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_AverageMPG : 1|10@0+ (1,0) [0|0] "" H_U + SG_ TMU_TotalMPG : 23|10@0+ (1,0) [0|0] "" H_U + SG_ TMU_RewardStar : 37|14@0+ (1,0) [0|0] "" H_U + +BO_ 64 TMU_HU_E_01: 8 TMU + SG_ TMU_DisMode : 3|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_AudSrcType : 7|4@0+ (1,0) [0|0] "" CLU,DATC,H_U + SG_ TMU_AudReqCmd : 9|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_LangCmd : 12|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_ServReq : 15|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_ErrorEvent : 23|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_BeepCmd : 25|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_eCall : 28|3@0+ (1,0) [0|0] "" H_U + +BO_ 62 HU_Navi_E_00: 8 H_U + SG_ Navi_SLIF_SpdUnit : 1|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SLIF_Frwinfo : 4|3@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SLIF_LinkClass : 7|3@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SLIF_SpdLimit : 15|8@0+ (1,0) [1|254] "" CGW,CLU,HUD + SG_ Navi_SLIFMapSource : 29|4@0+ (1,0) [0|8] "" CGW,CLU,HUD + SG_ Navi_SLIF_CountryCode : 23|10@0+ (1,0) [0|0] "" CGW,CLU,HUD + +BO_ 52 HU_DATC_E_02: 8 H_U + SG_ HU_DATC_DrTempUpDn : 1|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_PsTempUpDn : 3|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RlTempUpDn : 5|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RrTempUpDn : 7|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_MainBlower : 11|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_SubBlower : 15|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearBlower : 19|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATCRearPsModeSet : 23|4@0+ (1,0) [0|0] "" CGW,CLU + SG_ HU_DATC_FrontModeSet : 27|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearModeSet : 31|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_AutoSet : 33|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_OffReq : 35|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_IntakeSet : 37|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearOnOffSet : 39|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_AcSet : 41|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_AqsSet : 43|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_FrontDefog : 45|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearDefog : 47|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_ZoneControl : 49|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_CO2Set : 51|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ DATC_SmartVentOnOffSet : 53|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ DATC_ADSOnOffSet : 55|2@0+ (1,0) [0|0] "" CGW,CLU + SG_ HU_DATC_RearAutoDisp : 57|2@0+ (1,0) [0|0] "" CGW,CLU + SG_ HU_DATC_RearOffDisp : 59|2@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 308 DATC_PE_05: 8 CLU + SG_ DATC_PwrInfo : 3|4@0+ (1,0) [0|0] "" AMP,AVM,CUBIS,H_U,MON + SG_ DATC_AltL : 5|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_CarInfo : 7|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_ParkingBrake : 9|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_LowFuelWarn : 11|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_Rear_Off_Disp : 13|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_Rear_AutoDisp : 15|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_Rear_BlowerDisp : 19|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_DrSeatWarmerDisp : 22|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_SyncDisp : 27|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_RearDispCtrl : 31|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_RearDrModeDisp : 35|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_PsSeatWarmerDisp : 38|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_DrVentSeatDisp : 42|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_PSVentSeatDisp : 46|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_RrDefLed : 49|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_SmartVentOnOffStatus : 51|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_ADSOnOffStatus : 53|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_AcDisp_OSD : 55|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_PsModeDisp_OSD : 59|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_ModeDisp_OSD : 63|4@0+ (1,0) [0|0] "" H_U + +BO_ 307 DATC_PE_04: 8 CLU + SG_ DATC_DiagMode : 1|2@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_Rear_ChangeReqDisp : 3|2@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_Rear_ClimateScnDisp : 5|2@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_CO2OnOffStatus : 7|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_SelfDiagDisp : 15|8@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_RearBlwDisp_OSD : 19|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_AqsLevelOut : 23|4@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_RearModeDisp : 27|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_RearPsModeDisp : 31|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_FrontBlwDisp_Ps : 35|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_AutoDisp_Ps : 39|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_RearModeDisp_OSD : 43|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_RearPSModeDisp_OSD : 47|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_FrontBlwDisp_OSD : 51|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_FrontBlwDispPs_OSD : 55|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_Variant : 63|8@0+ (1,0) [0|0] "" H_U,IBOX,MON + +BO_ 306 DATC_PE_03: 8 CLU + SG_ DATC_ModeDisp : 3|4@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_TempUnit : 5|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_AutoDisp : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_IntakeDisp : 11|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_ChangeReqDisp : 13|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_AcDisp : 17|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_AqsDisp : 19|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_ClimateScnDisp : 21|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_DualDisp : 25|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_OffDisp : 27|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_OpSts : 30|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_RearManual : 33|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_FrDefLed : 37|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_SmartVentDisp : 39|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_AutoDefogBlink : 41|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_ADSDisp : 43|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_IonClean : 45|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_CO2Warning : 47|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_SubBlowerDisp : 51|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_BeepReq : 55|4@0+ (1,0) [0|0] "" H_U,KBD,MON + SG_ DATC_MainBlowerDisp : 59|4@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_PsModeDisp : 63|4@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 1329 DATC_P_02: 8 CLU + SG_ DATC_AmbientTemp_C : 7|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_AmbientTemp_F : 23|8@0+ (1,0) [0|0] "" H_U,MON + +BO_ 305 DATC_PE_02: 8 CLU + SG_ DATC_DrTempDispC : 7|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ DATC_Rear_DrTempDispC : 15|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ DATC_DrTempDispF : 23|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + SG_ DATC_Rear_DrTempDispF : 31|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + SG_ DATC_PsTempDispC : 39|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ Datc_RearPsTempDispC : 47|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ DATC_PsTempDispF : 55|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + SG_ DATC_RearPsTempDispF : 63|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + +BO_ 304 DATC_PE_01: 8 CLU + SG_ DATC_Type : 7|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerMMMajor : 15|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerMMMinor : 23|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerBDFMajor : 31|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerBDMinor : 39|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerCSMajor : 47|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerCSMinor : 55|8@0+ (1,0) [0|0] "" H_U,MON + +BO_ 291 HU_CLU_PE_07: 8 H_U + SG_ NV_DS_Curve : 3|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_Merge : 7|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_RailCross : 9|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_FallingRocks : 11|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_SchoolZone : 13|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_AccidentBlack : 15|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_SpeedBump : 17|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_RoadKill : 19|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_Downhill : 21|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_Fog : 23|2@0+ (1,0) [0|0] "" CLU + SG_ NV_Display_TG : 31|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_Charge : 39|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_Charge_Unit : 55|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_BarGraph100Level : 63|8@0+ (1,0) [0|100] "%" CLU,HUD + +BO_ 290 HU_CLU_PE_06: 8 H_U + SG_ NV_SD_SpdLimit2 : 3|4@0+ (10,0) [0|0] "km/h" CLU + SG_ NV_SD_SpdLimit1 : 7|4@0+ (10,0) [0|0] "km/h" CLU + SG_ NV_SD_EtcCam : 11|4@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_SpdLimit3 : 15|4@0+ (10,0) [0|0] "km/h" CLU + SG_ NV_SD_SignCam : 17|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_SignOverCam : 19|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_MobileCam : 21|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_FixedCam : 23|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_OverLoadCam : 25|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_ParkCam : 27|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_CutInCam : 29|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_BusOnlyCam : 31|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_ShoulderCam : 35|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_TrafficCam : 37|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_PlateRcgCam : 39|2@0+ (1,0) [0|0] "" CLU + +BO_ 286 HU_CLU_PE_10: 8 H_U + SG_ Navi_TBTInfo : 63|8@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 29 CLU_HU_E_00: 8 CLU + SG_ SYS_CLUVer : 7|16@0+ (1,0) [0|0] "" CUBIS,H_U + SG_ CLU_ClockInfoReq : 17|2@0+ (1,0) [0|0] "" H_U + SG_ CLU_DateInfoReq : 19|2@0+ (1,0) [0|0] "" H_U + +BO_ 27 AMP_HU_E_00: 8 AMP + SG_ SYS_AMPVer : 7|16@0+ (1,0) [0|0] "" H_U + +BO_ 23 HU_IPM_E_00: 8 H_U + SG_ C_ADrLNValueSet : 2|3@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrUNValueSet : 5|3@0+ (1,0) [0|0] "" DATC,IPM + SG_ SYS_Ver_Req : 7|2@0+ (1,0) [0|0] "" AMP,AVM,CLU,CUBIS,DATC,IPM + SG_ C_IMSRValueReq : 9|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_PSMNValueSet : 11|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_SCMNValueSet : 13|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrLURValueReq : 15|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ABuzzerNValueSet : 17|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_AlarmRValueReq : 19|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ArmWKeyNValueSet : 21|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_TwUnRValueReq : 23|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_TwUnNValueSet : 25|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_AutoMRFoldRValueReq : 27|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_AutoMRFoldNValueSet : 29|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrLRValueReq : 31|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ArmWKeyRValueReq : 33|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ABuzzerRValueReq : 35|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrURValueReq : 37|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_PSMRValueReq : 39|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_SCMRValueReq : 47|2@0+ (1,0) [0|0] "" DATC,IPM + +BO_ 277 HU_CLU_PE_02: 8 H_U + SG_ TBT_Display_Type : 7|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Side_Street : 15|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Direction : 31|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Distance_Turn_Point : 39|16@0+ (1,0) [0|0] "m" CLU,HUD + SG_ TBT_Combined_Side_Street : 51|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Scale : 55|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_DistancetoTurnPoint : 59|4@0+ (1,0) [0|0] "times" CLU,HUD + SG_ TBT_Bar_Graph_Level : 63|4@0+ (10,0) [0|100] "" CLU,HUD + +BO_ 276 HU_CLU_PE_01: 8 H_U + SG_ HU_OpState : 6|7@0+ (1,0) [0|0] "" AMP,CLU + SG_ HU_Navi_On_Off : 7|1@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_Preset_Number : 12|5@0+ (1,1) [1|30] "" AMP,CLU + SG_ HU_Tuner_Area : 15|3@0+ (1,0) [0|0] "" AMP,CLU + SG_ HU_Track_Number : 23|16@0+ (1,0) [0|0] "" CLU + SG_ HU_Play_time_Sec : 39|6@0+ (1,0) [0|0] "" CLU + SG_ HU_Play_time_Min : 33|7@0+ (1,0) [0|0] "" CLU + SG_ HU_Play_time_Hour : 42|6@0+ (1,0) [0|0] "" CLU + SG_ HU_Disc_select_No : 59|4@0+ (1,0) [0|0] "" CLU + SG_ HU_Frequency : 52|9@0+ (1,0) [0|0] "" AMP,CLU + +BO_ 17 HU_AMP_E_10: 8 H_U + SG_ AMP_Beep2VolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2Frequency : 15|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2Ch_OutputMask : 31|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2DurationOn : 47|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2DurationOff : 55|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2NumberOfCycles : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 15 HU_AMP_E_08: 8 H_U + SG_ AMP_MainVolumeSet : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_BalanceSet : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_FadeSet : 23|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_BassSet : 31|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_MidSet : 39|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_TrebleSet : 47|8@0+ (1,0) [0|0] "" AMP + +BO_ 14 HU_AMP_E_07: 8 H_U + SG_ AMP_HFVolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_HFMainAudioCut : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_HFChannelOutputMask : 23|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_HFChannelMuteMask : 39|16@0+ (1,0) [0|0] "" AMP + +BO_ 13 HU_AMP_E_06: 8 H_U + SG_ AMP_MTSVolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSMainAudioCut : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSChannelOutputMask : 23|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSChannelMuteMask : 39|16@0+ (1,0) [0|0] "" AMP + +BO_ 12 HU_AMP_E_05: 8 H_U + SG_ AMP_NaviVolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviMainAudioCut : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviChannelOutputMask : 23|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviChannelMuteMask : 39|16@0+ (1,0) [0|0] "" AMP + +BO_ 11 HU_AMP_E_04: 8 H_U + SG_ AMP_Drive : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_ConvertibleTop : 5|2@0+ (1,0) [0|0] "" AMP + +BO_ 10 HU_AMP_E_03: 8 H_U + SG_ AMP_CrtVehicleID : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_SPDIFMode : 11|4@0+ (1,0) [0|0] "" AMP + SG_ AMP_VersionReq : 17|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_UpdateStart : 25|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_UpdateEnd : 33|2@0+ (1,0) [0|0] "" AMP + +BO_ 9 HU_AMP_E_02: 8 H_U + SG_ AMP_Mute : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_RearSpMute : 3|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_SurroundMode : 5|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_VEQMode : 7|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_AudioMode : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_EQ : 17|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_Reset : 19|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_SPDIFMute : 21|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_DefaultBeep1 : 25|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_DefaultBeep2 : 29|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_BeatsMode : 33|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_VIPMode : 35|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_QLSMode : 37|2@0+ (1,0) [0|0] "" AMP + +BO_ 1288 HU_CLU_P_02: 8 H_U + SG_ NV_TIME_TYPE : 3|4@0+ (1,0) [0|0] "" CLU + SG_ NV_Hour : 15|8@0+ (1,0) [0|0] "" CLU + SG_ NV_Min : 23|8@0+ (1,0) [0|0] "" CLU + +BO_ 8 HU_AMP_E_01: 8 H_U + SG_ AMP_HFMode : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviMode : 3|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSMode : 5|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_VSCMode : 7|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1Mode : 9|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2Mode : 11|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_SDVCStep : 14|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_ASDMode : 18|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_SignalDoctor : 20|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_AutoVolume : 22|2@0+ (1,0) [0|0] "" AMP + +BO_ 1287 HU_CLU_P_01: 8 H_U + SG_ NV_DistToTurn_F1 : 3|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_Unit : 7|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_F3 : 11|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_F2 : 15|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_I1 : 23|16@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_I2 : 39|16@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_I3 : 55|16@0+ (1,0) [0|0] "" CLU + +BO_ 1286 HU_CLU_P_00: 8 H_U + SG_ NV_EstDist_F : 3|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstDist_Unit : 7|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstHour : 15|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstMin : 23|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_Azimuth : 31|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstDist_I : 39|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstimTimeType : 49|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ NV_EstimTimeFormat : 51|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + +BO_ 1284 HU_AMP_P_01: 8 H_U + SG_ HU_VehicleSpeed : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_SetMaxMainVolStep : 9|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_LKASWarningOn : 21|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_BSDWarningOn : 23|2@0+ (1,0) [0|0] "" AMP + +BO_ 256 HU_MON_PE_01: 8 H_U + SG_ HU_Type : 7|8@0+ (1,0) [0|0] "" AMP,CGW,CLU,HUD,KMA_TMU + SG_ HU_VerMajor : 15|8@0+ (1,0) [0|0] "" AMP,CLU,KMA_TMU,MON + SG_ HU_VerMinor : 23|8@0+ (1,0) [0|0] "" AMP,CLU,KMA_TMU,MON + SG_ HU_DistributeInfo : 31|8@0+ (1,0) [0|0] "" AMP,CGW,CLU,KMA_TMU,MON,RRC + SG_ HU_SubVerMajor : 39|8@0+ (1,0) [0|0] "" AMP,MON + SG_ HU_SubVerMinor : 47|8@0+ (1,0) [0|0] "" AMP,MON + SG_ HU_SDARSVersion : 55|8@0+ (1,0) [0|0] "" AMP,MON + SG_ HU_AdasSupport : 58|3@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 1092 NM_CLOCK: 8 CLOCK + SG_ Destination_CLOCK : 7|8@0+ (1,0) [0|0] "" HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CLOCK : 13|2@0+ (1,0) [0|0] "" HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CLOCK : 10|3@0+ (1,0) [0|0] "" HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1108 NM_HUD: 8 HUD + SG_ Destination_HUD : 7|8@0+ (1,0) [0|0] "" CLOCK,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_HUD : 13|2@0+ (1,0) [0|0] "" CLOCK,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_HUD : 10|3@0+ (1,0) [0|0] "" CLOCK,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1088 NM_H_U: 8 H_U + SG_ Destination_H_U : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_H_U : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_H_U : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1091 NM_DATC: 8 DATC + SG_ Destination_DATC : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_DATC : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_DATC : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1105 NM_CCP: 8 CCP + SG_ Destination_CCP : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CCP : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CCP : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1100 NM_KMA_TMU: 8 KMA_TMU + SG_ Destination_KMA_TMU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_KMA_TMU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_KMA_TMU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1098 NM_CUBIS: 8 CUBIS + SG_ Destination_CUBIS : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CUBIS : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CUBIS : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1099 NM_TMU: 8 TMU + SG_ Destination_TMU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_TMU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_TMU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1095 NM_IPM: 8 IPM + SG_ Destination_IPM : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_IPM : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_IPM : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1107 NM_RSE_R: 8 RSE_R + SG_ Destination_RSE_R : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_RSE_R : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_RSE_R : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1093 NM_RRC: 8 RRC + SG_ Destination_RRC : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_RRC : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_RRC : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1109 NM_CGW: 8 CGW + SG_ Destination_CGW : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CGW : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CGW : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1106 NM_RSE_L: 8 RSE_L + SG_ Destination_RSE_L : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_RSE_L : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_RSE_L : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1096 NM_AMP: 8 AMP + SG_ Destination_AMP : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_AMP : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_AMP : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1103 NM_EDT: 8 EDT + SG_ Destination_EDT : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_EDT : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_EDT : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1110 NM_SWRC: 8 SWRC + SG_ Destination_SWRC : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_SWRC : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_SWRC : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1102 NM_IBOX: 8 IBOX + SG_ Destination_IBOX : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_IBOX : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_IBOX : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1101 NM_CLU: 8 CLU + SG_ Destination_CLU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CLU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CLU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,FHCU,ASD,MON,AVM,KBD + +BO_ 1097 NM_FHCU: 8 FHCU + SG_ Destination_FHCU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_FHCU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,ASD,MON,AVM,KBD + SG_ NMCommandCode_FHCU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,ASD,MON,AVM,KBD + +BO_ 1094 NM_ASD: 8 ASD + SG_ Destination_ASD : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,MON,AVM,KBD + SG_ NMSleepFlag_ASD : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,MON,AVM,KBD + SG_ NMCommandCode_ASD : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,MON,AVM,KBD + +BO_ 1089 NM_MON: 8 MON + SG_ Destination_MON : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,AVM,KBD + SG_ NMSleepFlag_MON : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,AVM,KBD + SG_ NMCommandCode_MON : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,AVM,KBD + +BO_ 1104 NM_AVM: 8 AVM + SG_ Destination_AVM : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,KBD + SG_ NMSleepFlag_AVM : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,KBD + SG_ NMCommandCode_AVM : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,KBD + +BO_ 1090 NM_KBD: 8 KBD + SG_ Destination_KBD : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM + SG_ NMSleepFlag_KBD : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM + SG_ NMCommandCode_KBD : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM + diff --git a/opendbc/hyundai_santa_fe_2019_ccan.dbc b/opendbc/hyundai_santa_fe_2019_ccan.dbc new file mode 100644 index 00000000000000..b9e654fa662bcb --- /dev/null +++ b/opendbc/hyundai_santa_fe_2019_ccan.dbc @@ -0,0 +1,1420 @@ +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_: IAP ODS _4WD BCM HUD DATC MDPS AAF_Tester AEMC SMK _4WD EPB CUBIS MTS TMU EVP CGW TPMS LPI DI_BOX SPAS EMS LCA TCU IBOX FATC AFLS FPCM SCC AHLS AVM ABS SNV OPI PGS SAS AAF Dummy LDWS_LKAS LVR ESC PSB CLU ECS ACU REA + +BO_ 1532 ODS13: 5 ODS + SG_ CR_Ods_ID : 0|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_Chksum_H : 8|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_Chksum_L : 16|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_RomID_H : 24|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_RomID_L : 32|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + +BO_ 1531 ODS12: 8 ODS + SG_ CR_Ods_SerNum0 : 0|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum3 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum4 : 32|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum5 : 40|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum6 : 48|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum7 : 56|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + +BO_ 1530 ODS11: 8 ODS + SG_ CF_Ods_PrcCmd : 1|1@1+ (1.0,0.0) [0.0|1.0] "" Dummy + SG_ CF_Ods_BtsFail : 3|1@1+ (1.0,0.0) [0.0|1.0] "" Dummy + SG_ CF_Ods_AcuRcvSN : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_EolCal : 5|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_PsFail : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_EcuFail : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_WgtStat : 8|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_OccStat : 16|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CR_Wcs_ErrStat : 32|8@1+ (1.0,0.0) [0.0|63.0] "" ACU + SG_ CR_Wcs_ClassStat : 40|8@1+ (1.0,0.0) [0.0|4.0] "" ACU,BCM + +BO_ 1017 ECS12: 4 ECS + SG_ Height_FL : 0|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_FR : 8|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_RL : 16|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_RR : 24|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + +BO_ 1268 SPAS12: 8 SPAS + SG_ CF_Spas_HMI_Stat : 0|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Spas_Disp : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS + SG_ CF_Spas_FIL_Ind : 10|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FIR_Ind : 13|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FOL_Ind : 16|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FOR_Ind : 19|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_VolDown : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RIL_Ind : 24|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_RIR_Ind : 27|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FLS_Alarm : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_ROL_Ind : 32|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_ROR_Ind : 35|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FCS_Alarm : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_FI_Ind : 40|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_RI_Ind : 43|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FRS_Alarm : 46|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_FR_Alarm : 48|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Spas_RR_Alarm : 50|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Spas_BEEP_Alarm : 52|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Spas_StatAlarm : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Spas_RLS_Alarm : 57|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RCS_Alarm : 59|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RRS_Alarm : 61|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1265 CLU11: 4 CLU + SG_ CF_Clu_CruiseSwState : 0|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_CruiseSwMain : 3|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_SldMainSW : 4|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Clu_ParityBit1 : 5|1@1+ (1.0,0.0) [0.0|1.0] "pulse count" EMS + SG_ CF_Clu_VanzDecimal : 6|2@1+ (0.125,0.0) [0.0|0.375] "" EMS + SG_ CF_Clu_Vanz : 8|9@1+ (0.5,0.0) [0.0|255.5] "km/h or MPH" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_SPEED_UNIT : 17|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_DetentOut : 18|1@1+ (1.0,0.0) [0.0|1.0] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_RheostatLevel : 19|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_CluInfo : 24|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_AmpInfo : 25|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_AliveCnt1 : 28|4@1+ (1.0,0.0) [0.0|15.0] "" AHLS,EMS,EPB,LDWS_LKAS,MDPS,SCC + +BO_ 1492 TMU_GW_PE_01: 8 CLU + SG_ TMU_IVRActivity : 0|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ TMU_PhoneActivity : 2|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1491 HU_DATC_PE_00: 8 CLU + SG_ HU_VRActivity : 0|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ HU_PhoneActivity : 2|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ BlowerNoiseControl : 4|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1490 HU_DATC_E_02: 8 CLU + SG_ HU_DATC_RearOnOffSet : 6|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ HU_DATC_ADSOnOffSet : 8|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1479 EMS21: 8 EMS + SG_ SCR_LEVEL_WARN_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ SCR_LEVEL_WARN : 1|3@1+ (1.0,0.0) [0.0|4.0] "" CLU + SG_ SCR_SYS_ERROR_WARN : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ SCR_SYSTEM_WARN_LAMP : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ SCR_INDUCEMENT_EXIT_COND : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ SCR_UREA_LEVEL : 16|8@1+ (0.5,0.0) [0.0|100.0] "%" CLU + SG_ SCR_NO_REMAINING_RESTARTS : 24|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ SCR_REMAINING_DISTANCE : 32|16@1+ (1.0,0.0) [0.0|25000.0] "km" CLU + +BO_ 1472 GW_Warning_PE: 8 BCM + SG_ Audio_VolumeDown : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Flh_Alarm : 48|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Fcnt_Alarm : 50|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Frh_Alarm : 52|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Rlh_Alarm : 56|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,PGS + SG_ Pas_Spkr_Rcnt_Alarm : 58|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Rrh_Alarm : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,PGS + +BO_ 1984 CAL_SAS11: 2 ESC + SG_ CCW : 0|4@1+ (1.0,0.0) [0.0|15.0] "" SAS + SG_ SAS_CID : 4|11@1+ (1.0,0.0) [0.0|2047.0] "" SAS + +BO_ 1456 CLU12: 4 CLU + SG_ CF_Clu_Odometer : 0|24@1+ (0.1,0.0) [0.0|1677721.4] "km" _4WD,AAF,BCM,CUBIS,EMS,EPB,IBOX,LDWS_LKAS,SCC,TPMS + +BO_ 688 SAS11: 5 MDPS + SG_ SAS_Angle : 0|16@1- (0.1,0.0) [-3276.8|3276.7] "Deg" _4WD,ACU,AFLS,AVM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU,_4WD,ACU,AFLS,AVM,BCM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU + SG_ SAS_Speed : 16|8@1+ (4.0,0.0) [0.0|1016.0] "" AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU,AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU + SG_ SAS_Stat : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ MsgCount : 32|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + SG_ CheckSum : 36|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + +BO_ 1441 ACU12: 8 ACU + SG_ CR_Acu_SN : 0|64@1+ (1.0,0.0) [0.0|0.0] "" ODS + +BO_ 1440 ACU11: 8 ACU + SG_ CF_Ods_SNRcv : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Ods_IDRcv : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Ods_RZReq : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Abg_DepInhEnt : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Abg_DepEnt : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_PasBkl_FltStat : 28|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_DriBkl_FltStat : 29|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_PasBkl_Stat : 30|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,ODS,PSB,TMU + SG_ CF_DriBkl_Stat : 31|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_SWL_Ind : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CUBIS,IBOX + SG_ CF_Acu_FltStat : 34|2@1+ (1.0,0.0) [0.0|3.0] "" CUBIS,IBOX + SG_ CF_Acu_ExtOfSab : 36|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,CUBIS,IBOX + SG_ CF_Acu_Dtc : 40|16@1+ (1.0,0.0) [0.0|65535.0] "" CUBIS,IBOX + SG_ CF_Acu_NumOfFlt : 56|8@1+ (1.0,0.0) [0.0|255.0] "" CUBIS,IBOX + +BO_ 1437 AHLS11: 8 AHLS + SG_ CF_Ahls_WarnLamp : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Ahls_WarnMsg : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1434 PSB11: 2 PSB + SG_ PSB_LH_FAIL : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PSB_LH_TGL : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ PSB_LH_ACT : 3|4@1+ (1.0,0.0) [0.0|4.0] "" Dummy + SG_ PSB_RH_FAIL : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PSB_RH_TGL : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ PSB_RH_ACT : 11|4@1+ (1.0,0.0) [0.0|4.0] "" Dummy + +BO_ 916 TCS13: 8 ESC + SG_ aBasis : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ BrakeLight : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,SCC + SG_ DCEnable : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ AliveCounterTCS : 13|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,SCC + SG_ ACCReqLim : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ TQI_ACC : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS + SG_ ACCEL_REF_ACC : 32|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ ACCEnable : 43|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ DriverOverride : 45|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ StandStill : 47|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ CheckSum_TCS3 : 48|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,SCC + SG_ ACC_EQUIP : 52|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ PBRAKE_ACT : 53|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ ACC_REQ : 54|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ DriverBraking : 55|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ CF_VSM_Coded : 56|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_VSM_Avail : 57|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,SCC + SG_ CF_VSM_Handshake : 59|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_DriBkeStat : 60|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_VSM_ConfSwi : 61|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ AEB_EQUIP : 63|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + +BO_ 1427 TPMS11: 6 BCM + SG_ TPMS_W_LAMP : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ TREAD_W_LAMP : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ POS_FL_W_LAMP : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_FR_W_LAMP : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RL_W_LAMP : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RR_W_LAMP : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ STATUS_TPMS : 8|3@1+ (1.0,0.0) [0.0|0.0] "" CLU + SG_ UNIT : 11|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PRESSURE_FL : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_FR : 24|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_RL : 32|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_RR : 40|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + +BO_ 915 TCS12: 4 ESC + SG_ SA_COUNT : 0|16@1+ (2.0,-32768.0) [-32768.0|98302.0] "" _4WD,ACU,MDPS + SG_ SA_Z_COUNT : 16|15@1+ (2.0,-32768.0) [-32768.0|32766.0] "" _4WD,ACU,MDPS + SG_ SA_Z_FLAG : 31|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,MDPS + +BO_ 1170 EMS19: 8 EMS + SG_ CF_Ems_BrkReq : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX,TCU + SG_ CF_Ems_DnShftReq : 1|4@1+ (1.0,0.0) [0.0|14.0] "" IBOX,TCU + SG_ CF_Ems_RepModChk : 5|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ CF_Ems_AAFOpenReq : 7|1@1+ (1.0,0.0) [0.0|1.0] "" AAF,IBOX + SG_ CF_Ems_DecelReq : 8|12@1+ (0.0010,-4.094) [-4.094|0.0] "m/s^2" ESC,IBOX,TCU + SG_ CR_Ems_BstPre : 20|12@1+ (1.322,0.0) [0.0|4094.0] "hPa" CLU,IBOX + SG_ CR_Ems_EngOilTemp : 32|8@1+ (0.75,-40.0) [0.0|254.0] "deg" CLU,IBOX + SG_ DPF_LAMP_STAT : 40|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ BAT_LAMP_STAT : 42|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_ModeledAmbTemp : 48|8@1+ (0.5,-41.0) [-41.0|85.5] "deg" AAF,IBOX + SG_ CF_Ems_OPSFail : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_AliveCounterEMS9 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + SG_ CF_Ems_ChecksumEMS9 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + +BO_ 1425 AFLS11: 2 AFLS + SG_ AFLS_STAT : 1|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Afls_TrfChgStat : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Afls_LedHLStat : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 912 SPAS11: 7 SPAS + SG_ CF_Spas_Stat : 0|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,MDPS + SG_ CF_Spas_TestMode : 4|2@1+ (1.0,0.0) [0.0|3.0] "" MDPS + SG_ CR_Spas_StrAngCmd : 8|16@1- (0.1,0.0) [-3276.8|3276.7] "" MDPS + SG_ CF_Spas_BeepAlarm : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Spas_Mode_Seq : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_AliveCnt : 32|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Spas_Chksum : 40|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Spas_PasVol : 48|3@1+ (1.0,0.0) [0.0|7.0] "" CGW,CLU + +BO_ 1168 EPB11: 7 EPB + SG_ EPB_I_LAMP : 0|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU,CUBIS,ESC,IBOX + SG_ EPB_F_LAMP : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,ESC,IBOX + SG_ EPB_ALARM : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ EPB_CLU : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,ESC + SG_ EPB_SWITCH : 16|2@1+ (1.0,0.0) [0.0|3.0] "" ESC,SCC + SG_ EPB_RBL : 18|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,ESC + SG_ EPB_STATUS : 19|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,ESC,SCC,TCU + SG_ EPB_FRC_ERR : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,SCC,TCU + SG_ EPB_DBF_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ ESP_ACK : 25|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ EPB_DBF_REQ : 26|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ EPB_FAIL : 29|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,SCC + SG_ EPB_FORCE : 32|12@1+ (1.0,-1000.0) [-1000.0|3000.0] "" ESC + SG_ EPB_DBF_DECEL : 48|8@1+ (0.01,0.0) [0.0|2.54] "g" ESC + +BO_ 399 EMS_H12: 8 EMS + SG_ R_TqAcnApvC : 0|8@1+ (0.2,0.0) [0.0|51.0] "Nm" DATC,IBOX + SG_ R_PAcnC : 8|8@1+ (125.0,0.0) [0.0|31875.0] "hPa" DATC,IBOX + SG_ TQI_B : 16|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ABS,ESC,IBOX + SG_ SLD_VS : 24|8@1+ (1.0,0.0) [0.0|255.0] "km/h" CLU,IBOX + SG_ CF_CdaStat : 32|3@1+ (1.0,0.0) [0.0|7.0] "" AEMC,IBOX,TCU + SG_ CF_Ems_IsgStat : 35|3@1+ (1.0,0.0) [0.0|7.0] "" ABS,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,MDPS,SMK,TCU + SG_ CF_Ems_OilChg : 38|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_EtcLimpMod : 39|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ R_NEngIdlTgC : 40|8@1+ (10.0,0.0) [0.0|2550.0] "rpm" DATC,IBOX,TCU + SG_ CF_Ems_UpTarGr : 48|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_DownTarGr : 49|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_DesCurGr : 50|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX + SG_ CF_Ems_SldAct : 54|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_SldPosAct : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_HPresStat : 56|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ CF_Ems_IsgBuz : 57|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_IdlStpFCO : 58|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_FCopen : 59|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_ActEcoAct : 60|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ CF_Ems_EngRunNorm : 61|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,IBOX,TCU + SG_ CF_Ems_IsgStat2 : 62|2@1+ (2.0,0.0) [0.0|3.0] "" CLU,IBOX,TCU + +BO_ 1419 LCA11: 8 LCA + SG_ CF_Lca_Stat : 0|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Rcta_Stat : 4|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Lca_IndLeft : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Rcw_Stat : 10|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_RCW_Warning : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Lca_IndRight : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Lca_SndWan_Stat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_FR_SndWan : 20|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_FL_SndWan : 21|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_RR_SndWan : 22|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_RL_SndWan : 23|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_Lca_IndBriLeft : 24|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_Lca_IndBriRight : 32|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndBriLeft : 40|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndBriRight : 48|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndLeft : 56|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_RCTA_IndRight : 58|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_SndWarnForClu : 60|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 906 ABS11: 8 ABS + SG_ ABS_DEF : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,EMS,SPAS,TCU + SG_ EBD_DEF : 1|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,SPAS,TCU + SG_ ABS_ACT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,EPB,SPAS,TCU + SG_ ABS_W_LAMP : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,CUBIS,MTS,TMU + SG_ EBD_W_LAMP : 4|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ ABS_DIAG : 5|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ ESS_STAT : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,BCM,CLU,EMS + +BO_ 903 WHL_PUL11: 6 ABS + SG_ WHL_PUL_FL : 0|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_FR : 8|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RL : 16|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RR : 24|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_DIR_FL : 32|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_FR : 34|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RL : 36|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RR : 38|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_PUL_Chksum : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EPB,SPAS,TPMS,EPB,LCA,LDWS_LKAS,SPAS,TPMS + +BO_ 1415 TMU11: 8 IBOX + SG_ CF_Tmu_VehSld : 0|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Tmu_VehImmo : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Tmu_ReqRepCnd : 2|2@1+ (1.0,0.0) [0.0|3.0] "" EMS + SG_ CF_Tmu_AirconCtr : 4|1@1+ (1.0,0.0) [0.0|1.0] "" DATC + SG_ CF_Tmu_TempMd : 5|1@1+ (1.0,0.0) [0.0|1.0] "" DATC + SG_ CF_Tmu_TempSet : 6|16@1+ (1.0,0.0) [0.0|20.0] "" DATC + SG_ CF_Tmu_DefrostCtr : 22|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,FATC + SG_ CF_Tmu_AliveCnt1 : 56|4@1+ (1.0,0.0) [0.0|15.0] "" EMS + +BO_ 902 WHL_SPD11: 8 ABS + SG_ WHL_SPD_FL : 0|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_FR : 16|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,ACU,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RL : 32|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,BCM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,BCM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RR : 48|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_AliveCounter_LSB : 14|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_AliveCounter_MSB : 30|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_LSB : 46|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_MSB : 62|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1414 EVP11: 3 EVP + SG_ CF_Evp_Stat : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1412 AAF11: 8 AAF + SG_ CF_Aaf_ActFlapStatus : 0|2@1+ (1.0,0.0) [0.0|3.0] "" AAF_Tester + SG_ CF_Aaf_ModeStatus : 2|3@1+ (1.0,0.0) [0.0|7.0] "" AAF_Tester + SG_ CF_Aaf_WrnLamp : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Aaf_ErrStatus : 6|10@1+ (1.0,0.0) [0.0|1023.0] "" AAF_Tester,EMS + SG_ CF_Aaf_OpenRqSysAct : 16|8@1+ (1.0,0.0) [0.0|255.0] "" AAF_Tester + SG_ CF_Aaf_PStatus : 24|8@1+ (1.0,0.0) [0.0|100.0] "%" AAF_Tester + SG_ CF_Aaf_OpenRqSysSol : 32|8@1+ (1.0,0.0) [0.0|255.0] "" AAF_Tester + SG_ CF_Aaf_SolFlapStatus : 40|2@1+ (1.0,0.0) [0.0|3.0] "" AAF_Tester + SG_ CF_Aaf_MilOnReq : 42|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 900 EMS17: 8 EMS + SG_ CF_Ems_PkpCurMSV : 0|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_HolCurMSV : 8|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_InjVBnkAct : 16|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_InjVActSet : 24|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_DiagFulHDEV : 32|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_SwiOffIC1 : 33|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_SwiOffIC2 : 34|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_DiagReqHDEV : 38|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CR_Ems_DutyCycMSV : 40|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" DI_BOX + SG_ CR_Ems_BatVolRly : 48|8@1+ (0.1,0.0) [0.0|25.5] "V" DI_BOX + +BO_ 387 REA11: 8 REA + SG_ CF_EndBst_PwmDuH : 0|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PwmDuL : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PwmFqOutRng : 2|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_HbriOverCur : 3|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_HbriOverTemp : 4|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PosSnsKOR : 6|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PosSnsOSOR : 7|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_EepFlt : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_RomFlt : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_RamFlt : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_CanFlt : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_AgH : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_AgL : 13|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_ORVol : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CR_EndBst_ActPos : 16|16@1+ (0.117,0.0) [1.989|118.053] "" EMS + SG_ CR_EndBst_DemPos : 32|16@1+ (0.117,0.0) [0.0|119.691] "" EMS + SG_ CR_EndBst_HbriPwr : 48|16@1+ (0.045,0.0) [0.0|99.99] "%" EMS + +BO_ 1411 CUBIS11: 8 CUBIS + SG_ CF_Cubis_HUDisp : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + +BO_ 899 FATC11: 8 DATC + SG_ CR_Fatc_TqAcnOut : 0|8@1+ (0.2,0.0) [0.0|50.8] "Nm" EMS,IBOX + SG_ CF_Fatc_AcnRqSwi : 8|1@1+ (1.0,0.0) [0.0|1.0] "" AAF,EMS,IBOX + SG_ CF_Fatc_AcnCltEnRq : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_EcvFlt : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_BlwrOn : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_FATC_Iden : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Fatc_BlwrMax : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX + SG_ CF_Fatc_EngStartReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_IsgStopReq : 16|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_CtrInf : 17|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,IBOX + SG_ CF_Fatc_MsgCnt : 20|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + SG_ CR_Fatc_OutTemp : 24|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" BCM,CLU,EMS,IBOX,SPAS,TCU,TPMS + SG_ CR_Fatc_OutTempSns : 32|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" AAF,AHLS,CLU,EMS,IBOX,SPAS,TCU + SG_ CF_Fatc_Compload : 40|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,IBOX + SG_ CF_Fatc_ActiveEco : 43|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Fatc_AutoActivation : 44|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX + SG_ CF_Fatc_DefSw : 45|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,IBOX + SG_ CF_Fatc_PtcRlyStat : 46|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_ChkSum : 56|8@1+ (1.0,0.0) [0.0|255.0] "" EMS,IBOX,SPAS + +BO_ 129 EMS_DCT12: 8 EMS + SG_ CR_Ems_SoakTimeExt : 0|6@1+ (5.0,0.0) [0.0|315.0] "Min" TCU + SG_ BRAKE_ACT : 6|2@1+ (1.0,0.0) [0.0|3.0] "" TCU + SG_ CF_Ems_EngOperStat : 8|8@1+ (1.0,0.0) [0.0|255.0] "" TCU + SG_ CR_Ems_IndAirTemp : 16|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" TCU + SG_ CF_Ems_Alive2 : 56|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Ems_ChkSum2 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 897 MDPS11: 8 MDPS + SG_ CF_Mdps_WLmp : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,EMS,IBOX,SPAS + SG_ CF_Mdps_Flex : 2|3@1+ (1.0,0.0) [0.0|3.0] "" CLU,LDWS_LKAS + SG_ CF_Mdps_FlexDisp : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Mdps_Stat : 7|4@1+ (1.0,0.0) [0.0|15.0] "" SPAS + SG_ CR_Mdps_DrvTq : 11|12@1+ (1.0,-2048.0) [-2048.0|2046.0] "" SPAS + SG_ CF_Mdps_ALTRequest : 23|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CR_Mdps_StrAng : 24|16@1- (0.1,0.0) [-3276.8|3276.7] "Deg" SPAS + SG_ CF_Mdps_AliveCnt : 40|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_Chksum : 48|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_SPAS_FUNC : 57|1@1+ (1.0,0.0) [0.0|1.0] "flag" SPAS + SG_ CF_Mdps_LKAS_FUNC : 58|1@1+ (1.0,0.0) [0.0|1.0] "flag" LDWS_LKAS + SG_ CF_Mdps_CurrMode : 59|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Mdps_Type : 61|2@1+ (1.0,0.0) [0.0|2.0] "" LDWS_LKAS,SPAS + +BO_ 896 DI_BOX13: 8 DI_BOX + SG_ CF_DiBox_HPreInjVConfStat : 0|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVStat1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVStat2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVPkp : 24|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVBpt : 32|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_ErrRegFrtMSV : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_ErrRegSedMSV : 48|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SPIErrSedMSV : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_SPIErrFrtMSV : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IDErrSedMSV : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IDErrFrtMSV : 59|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IniStatMSV : 60|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 640 EMS13: 8 EMS + SG_ LV_FUEL_TYPE_ECU : 0|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,LPI,SMK + SG_ LV_BFS_CFIRM : 1|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_CRASH : 2|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_VB_OFF_ACT : 3|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_GSL_MAP M : 4|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_ENG_TURN : 5|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ ERR_FUEL : 8|8@1+ (1.0,0.0) [0.0|255.0] "" LPI + SG_ EOS : 16|8@1+ (1.0,0.0) [0.0|255.0] "" LPI + SG_ TCO : 24|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" LPI + SG_ N_32 : 32|8@1+ (32.0,0.0) [0.0|8160.0] "rpm" LPI + SG_ MAF : 40|8@1+ (5.447,0.0) [0.0|1388.985] "mg/TDC" LPI + SG_ TIA : 48|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" LPI + SG_ MAP m1 : 56|8@1+ (0.47058,0.0) [0.0|119.9979] "kPa" LPI + SG_ AMP m0 : 56|8@1+ (21.22,0.0) [0.0|5411.1] "hPa" LPI + +BO_ 128 EMS_DCT11: 8 EMS + SG_ PV_AV_CAN : 0|8@1+ (0.3906,0.0) [0.0|99.603] "%" TCU + SG_ TQ_STND : 8|6@1+ (10.0,0.0) [0.0|630.0] "Nm" TCU + SG_ F_N_ENG : 14|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ F_SUB_TQI : 15|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ N : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" TCU + SG_ TQI_ACOR : 32|8@1+ (0.390625,0.0) [0.0|99.6094] "%" IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0.0) [0.0|99.6094] "%" TCU + SG_ TQI : 48|8@1+ (0.390625,0.0) [0.0|99.609375] "%" TCU + SG_ CF_Ems_Alive : 56|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Ems_ChkSum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 1407 HU_MON_PE_01: 8 CLU + SG_ HU_Type : 0|8@1+ (1.0,0.0) [0.0|255.0] "" AVM,PGS + +BO_ 127 CGW5: 8 BCM + SG_ C_StopLampLhOpenSts : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_StopLampRhOpenSts : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HMSLOpenSts : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampLowLhOpenSts : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampLowRhOpenSts : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampHighLhOpenSts : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampHighRhOpenSts : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_DRLLampLhOpenSts : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_DRLLampRhOpenSts : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearFOGLhOpenSts : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearFOGRhOpenSts : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontFOGLhOpenSts : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontFOGRhOpenSts : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearEXTTailLhOpenSts : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearEXTTailRhOpenSts : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontEXTTailLhOpenSts : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontEXTTailRhOpenSts : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearTSIGLhOpenSts : 17|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearTSIGRhOpenSts : 18|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontTSIGLhOpenSts : 19|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontTSIGRhOpenSts : 20|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SBendingLhOpenSts : 21|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SBendingRhOpenSts : 22|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_LicensePlateLhOpenSts : 23|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_LicensePlateRhOpenSts : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1151 ESP11: 6 ESC + SG_ AVH_STAT : 0|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,TCU + SG_ LDM_STAT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" EPB,TCU + SG_ REQ_EPB_ACT : 3|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,TCU + SG_ REQ_EPB_STAT : 5|1@1+ (1.0,0.0) [0.0|1.0] "" EPB + SG_ ECD_ACT : 6|1@1+ (1.0,0.0) [0.0|1.0] "" EPB + SG_ _4WD_LIM_REQ : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS + SG_ ROL_CNT_ESP : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EPB,TCU + SG_ _4WD_TQC_LIM : 16|16@1+ (1.0,0.0) [0.0|65535.0] "Nm" _4WD,EMS + SG_ _4WD_CLU_LIM : 32|8@1+ (0.390625,0.0) [0.0|99.609375] "%" _4WD,EMS + SG_ _4WD_OPEN : 40|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,EMS + SG_ _4WD_LIM_MODE : 42|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD + +BO_ 1397 HU_AVM_E_00: 8 CLU + SG_ HU_AVM_Cal_Cmd : 0|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_Cal_Method : 4|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_Save_Controlpoint : 6|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_PT_X : 8|12@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_RearViewPointOpt : 20|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_PT_Y : 24|12@1+ (1.0,0.0) [0.0|4095.0] "" AVM,PGS + SG_ HU_AVM_FrontViewPointOpt : 36|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_SelectedMenu : 40|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,PGS + SG_ HU_AVM_CameraOff : 45|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_Option : 48|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_CrossLineMove_Cmd : 52|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_RearView_Option : 56|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_FrontView_Option : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + +BO_ 1395 HU_AVM_E_01: 8 CLU + SG_ HU_PGSSelectedMenu : 0|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_PGSOption : 8|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,PGS + SG_ HU_AVM_ParkingAssistMenu : 56|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_ParkingAssistSB : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + +BO_ 1393 OPI11: 5 OPI + SG_ CR_Opi_Spd_Rpm : 0|8@1+ (20.0,0.0) [0.0|3500.0] "rpm" TCU + SG_ CF_Opi_Over_Temp : 8|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Over_Cur : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Over_Vol : 10|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Hall_Fail : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Flt : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Motor_Dir : 15|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Romver : 16|8@1+ (1.0,0.0) [0.0|255.0] "" TCU + SG_ CF_Opi_PWM_Rate : 24|12@1+ (1.0,0.0) [0.0|100.0] "%" TCU + +BO_ 625 LPI11: 8 LPI + SG_ FUP_LPG_MMV : 0|8@1+ (128.0,0.0) [0.0|32640.0] "hPa" EMS + SG_ LV_FUEL_TYPE_BOX : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_BFS_IN_PROGRESS : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_GAS_OK : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_FUP_ENA_THD : 11|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,EMS,SMK + SG_ LPI_OBD : 12|4@1+ (1.0,0.0) [0.0|15.0] "" EMS + SG_ ERR_GAS : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ FAC_TI_GAS_COR : 24|16@1+ (3.05E-5,0.0) [0.0|1.9988175] "" EMS + SG_ FTL_AFU : 40|8@1+ (0.392,0.0) [0.0|99.96] "%" EMS + SG_ BFS_CYL : 48|8@1+ (1.0,0.0) [0.0|6.0] "Cyl Nr." EMS + SG_ LV_PRE_CDN_LEAK : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_CONF_INJECTION_DELAY : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_LPG_SW_DRIVER_REQ : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 356 VSM11: 4 ESC + SG_ CR_Esc_StrTqReq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" MDPS + SG_ CF_Esc_Act : 12|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,MDPS + SG_ CF_Esc_CtrMode : 13|3@1+ (1.0,0.0) [0.0|7.0] "" MDPS + SG_ CF_Esc_Def : 16|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Esc_AliveCnt : 17|4@1+ (1.0,0.0) [0.0|15.0] "" LDWS_LKAS,MDPS + SG_ CF_Esc_Chksum : 24|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,MDPS + +BO_ 1379 PGS_HU_PE_01: 8 PGS + SG_ PGS_State : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ PGS_ParkGuideState : 8|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ PGS_Option : 16|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ PGS_Version : 32|16@1+ (1.0,0.0) [0.0|65535.0] "" CLU + +BO_ 354 TCU_DCT13: 3 TCU + SG_ Clutch_Driving_Tq : 0|10@1+ (1.0,-512.0) [0.0|0.0] "Nm" ESC + SG_ Cluster_Engine_RPM : 10|13@1+ (0.9766,0.0) [0.0|0.0] "" CLU + SG_ Cluster_Engine_RPM_Flag : 23|1@1+ (1.0,0.0) [0.0|0.0] "" CLU + +BO_ 1378 HUD11: 4 HUD + SG_ CF_Hud_HeightStaus : 0|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ CF_Hud_PBackStatus : 6|2@1+ (1.0,0.0) [0.0|0.0] "" BCM,CLU + SG_ CF_Hud_Brightness : 8|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + +BO_ 608 EMS16: 8 EMS + SG_ TQI_MIN : 0|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ TQI : 8|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ TQI_TARGET : 16|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EPB,ESC,IBOX,TCU + SG_ GLOW_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,IBOX,SMK + SG_ CRUISE_LAMP_M : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ CRUISE_LAMP_S : 26|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ PRE_FUEL_CUT_IN : 27|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ENG_STAT : 28|3@1+ (1.0,0.0) [0.0|7.0] "" ABS,AHLS,AVM,BCM,CLU,EPB,ESC,EVP,FPCM,IBOX,LCA,LDWS_LKAS,MDPS,SCC,SMK,TCU + SG_ SOAK_TIME_ERROR : 31|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,EPB,IBOX,TCU + SG_ SOAK_TIME : 32|8@1+ (1.0,0.0) [0.0|255.0] "Min" _4WD,DATC,EPB,IBOX,TCU + SG_ TQI_MAX : 40|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ SPK_TIME_CUR : 48|8@1+ (0.375,-35.625) [-35.625|60.0] "" IBOX,TCU + SG_ Checksum : 56|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ AliveCounter : 60|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Ems_AclAct : 62|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,SCC + +BO_ 1371 AVM_HU_PE_00: 8 AVM + SG_ AVM_View : 0|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ AVM_ParkingAssist_BtnSts : 5|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ AVM_Display_Message : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ AVM_Popup_Msg : 16|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Ready : 20|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_ParkingAssist_Step : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_FrontBtn_Type : 28|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Option : 32|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_FrontViewPointOpt : 36|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_RearView_Option : 40|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_FrontView_Option : 44|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Version : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" CLU + +BO_ 1370 HU_AVM_PE_00: 8 CLU + SG_ HU_AVM_Status : 0|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + +BO_ 1369 CGW4: 8 BCM + SG_ CF_Gway_MemoryP1Cmd : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_MemoryP2Cmd : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackP1Cmd : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackP2Cmd : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_StrgWhlHeatedState : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackStopCmd : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,HUD + SG_ CF_Gway_StaticBendLhAct : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_StaticBendRhAct : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_DrvWdwStat : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RLWdwState : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RRWdwState : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_AstWdwStat : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_MemoryEnable : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBACKStopCmd : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBACKStop : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,HUD + SG_ CF_Gway_IMSBuzzer : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_DrvSeatBeltInd : 36|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_AstSeatBeltInd : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RCSeatBeltInd : 40|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RLSeatBeltInd : 42|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RRSeatBeltInd : 44|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RrWiperHighSw : 46|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RrWiperLowSw : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1367 EngFrzFrm12: 8 EMS + SG_ PID_06h : 0|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_07h : 8|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_08h : 16|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_09h : 24|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_0Bh : 32|8@1+ (1.0,0.0) [0.0|255.0] "kPa" AAF,IBOX,TCU + SG_ PID_23h : 40|16@1+ (10.0,0.0) [0.0|655350.0] "kPa" AAF,IBOX,TCU + +BO_ 1366 EngFrzFrm11: 8 EMS + SG_ PID_04h : 0|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" AAF,TCU + SG_ PID_05h : 8|8@1+ (1.0,-40.0) [-40.0|215.0] "deg" AAF,TCU + SG_ PID_0Ch : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" AAF,TCU + SG_ PID_0Dh : 32|8@1+ (1.0,0.0) [0.0|255.0] "km/h" AAF,TCU + SG_ PID_11h : 40|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" AAF,TCU + SG_ PID_03h : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" AAF,TCU + +BO_ 1365 FPCM11: 8 FPCM + SG_ CR_Fpcm_LPActPre : 0|8@1+ (3.137254902,0.0) [0.0|800.0] "kPa" EMS + SG_ CF_Fpcm_LPPumpOverCur : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrHi : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrDisc : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrShort : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LPPumpDiscShort : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LP_System_Error : 13|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrSigErr : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LPCtrCirFlt : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 871 LVR12: 8 LVR + SG_ CF_Lvr_Gear : 32|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,TCU + +BO_ 872 LVR11: 8 LVR + SG_ CF_Lvr_GearInf : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,TCU + SG_ CF_Lvr_PRelStat : 4|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,SMK,TCU + SG_ CF_Lvr_BkeAct : 5|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Lvr_NFnStat : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Lvr_PosInf : 8|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_PosCpl : 12|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_UlkButStat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" TCU + SG_ CF_Lvr_PNStat : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lvr_ShtLkStat : 24|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_ShfErrInf : 28|20@1+ (1.0,0.0) [0.0|8191.0] "" CLU,TCU + SG_ CF_Lvr_AC : 48|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_CS : 52|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 1363 CGW2: 8 BCM + SG_ CF_Gway_GwayDiagState : 0|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_DDMDiagState : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SCMDiagState : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_PSMDiagState : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SJBDiagState : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IPMDiagState : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_LDMFail : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,LDWS_LKAS,LDWS_LKAS + SG_ CF_Gway_CLUSwGuiCtrl : 10|3@1+ (1.0,0.0) [0.0|63.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwGroup : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwMode : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwEnter : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_AutoLightValue : 16|1@1+ (1.0,0.0) [0.0|1.0] "" LCA,LCA + SG_ CF_Gway_BrakeFluidSw : 17|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_DrvSeatBeltInd : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_AvTail : 20|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,SNV,SNV + SG_ CF_Gway_RearFogAct : 21|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ExtTailAct : 22|1@1+ (1.0,0.0) [0.0|1.0] "" AVM,CLU,LCA,PGS,SPAS,AVM,LCA,PGS,SPAS + SG_ CF_Gway_RRDrSw : 23|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_RLDrSw : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IntTailAct : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CountryCfg : 26|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,Dummy + SG_ CF_Gway_WiperParkPosition : 32|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,EMS,LDWS_LKAS,AFLS,EMS,LDWS_LKAS + SG_ CF_Gway_HLLowLHFail : 33|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_HLLowRHFail : 34|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_ESCLFailWarn : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ESCLNotLockedWarn : 36|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ESCLNotUnlockWarn : 37|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IDoutWarn : 38|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ImmoLp : 40|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_BCMRKEID : 41|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_VehicleNotPWarn : 44|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_DeactivationWarn : 45|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_KeyBATDischargeWarn : 46|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SSBWarn : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SMKFobID : 48|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_SMKRKECmd : 51|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_AutoLightOption : 54|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_SJBDeliveryMode : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_KeyoutLp : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SMKDispWarn : 57|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,Dummy + SG_ CF_Gway_WngBuz : 61|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + +BO_ 339 TCS11: 8 ESC + SG_ TCS_REQ : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,TCU + SG_ MSR_C_REQ : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,EPB,SCC,TCU + SG_ TCS_PAS : 2|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,SCC,SPAS,TCU + SG_ TCS_GSC : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,TCU + SG_ CF_Esc_LimoInfo : 4|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,SCC + SG_ ABS_DIAG : 6|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB + SG_ ABS_DEF : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_DEF : 8|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_CTL : 9|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ ABS_ACT : 10|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ EBD_DEF : 11|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SPAS,TCU + SG_ ESP_PAS : 12|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,CLU,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_DEF : 13|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_CTL : 14|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ TCS_MFRN : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,EPB,TCU + SG_ DBC_CTL : 16|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ DBC_PAS : 17|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ DBC_DEF : 18|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ HAC_CTL : 19|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_PAS : 20|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_DEF : 21|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ ESS_STAT : 22|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,BCM,CLU,EMS,EPB + SG_ TQI_TCS : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_MSR : 32|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_SLW_TCS : 40|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ CF_Esc_BrkCtl : 48|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ BLA_CTL : 49|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CGW,CLU + SG_ AliveCounter_TCS1 : 52|4@1+ (1.0,0.0) [0.0|14.0] "" EMS,EPB,LDWS_LKAS + SG_ CheckSum_TCS1 : 56|8@1+ (1.0,0.0) [0.0|255.0] "" EMS,EPB,LDWS_LKAS + +BO_ 1362 SNV11: 4 SNV + SG_ CF_SNV_DisplayControl : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,HUD + SG_ CF_Snv_BeepWarning : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,HUD + SG_ CF_Snv_WarningMessage : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,HUD + SG_ CF_Snv_DetectionEnable : 7|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,HUD + SG_ CF_Snv_PedestrianDetect : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,HUD + SG_ CF_Snv_IRLampControl : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,HUD + +BO_ 593 MDPS12: 8 MDPS + SG_ CR_Mdps_StrColTq : 0|11@1+ (0.0078125,-8.0) [-8.0|7.9921875] "Nm" LDWS_LKAS + SG_ CF_Mdps_Def : 11|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_Mdps_ToiUnavail : 12|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_ToiActive : 13|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_ToiFlt : 14|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_FailStat : 15|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_MsgCount2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" ESC,LDWS_LKAS + SG_ CF_Mdps_Chksum2 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ESC,LDWS_LKAS + SG_ CF_Mdps_SErr : 37|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CR_Mdps_StrTq : 40|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" ESC + SG_ CR_Mdps_OutTq : 52|12@1+ (0.1,-204.8) [-204.8|204.7] "" ESC,LDWS_LKAS + +BO_ 1360 IAP11: 3 IAP + SG_ CF_Iap_EcoPmodSwi : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Iap_EcoPmodAct : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Iap_ReqWarn : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1356 TCU_DCT14: 8 TCU + SG_ Vehicle_Stop_Time : 0|5@1+ (1.0,0.0) [0.0|0.0] "" CLU + SG_ HILL_HOLD_WARNING : 5|1@1+ (1.0,0.0) [0.0|0.0] "" CLU + +BO_ 1353 BAT11: 8 EMS + SG_ BAT_SNSR_I : 0|16@1+ (0.01,-327.0) [-327.0|328.0] "A" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOC : 16|8@1+ (1.0,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_V : 24|14@1+ (0.0010,6.0) [6.0|18.0] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Temp : 38|9@1- (0.5,-40.0) [-40.0|125.0] "deg" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_State : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOH : 48|7@1+ (1.0,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Invalid : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOF : 56|7@1+ (0.1,0.0) [0.0|12.0] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Error : 63|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + +BO_ 1351 EMS15: 8 EMS + SG_ ECGPOvrd : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX,SCC + SG_ QECACC : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ ECFail : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ SwitchOffCondExt : 3|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ BLECFail : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ CF_Ems_IsaAct : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ FA_PV_CAN : 8|8@1+ (0.3906,0.0) [0.0|99.2] "%" IBOX,LDWS_LKAS,TCU + SG_ IntAirTemp : 16|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" _4WD,ECS,EPB,IBOX,TCU + SG_ STATE_DC_OBD : 24|7@1+ (1.0,0.0) [0.0|127.0] "" IBOX,TCU + SG_ INH_DC_OBD : 31|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ CTR_IG_CYC_OBD : 32|16@1+ (1.0,0.0) [0.0|65535.0] "" ACU,IBOX,TCU + SG_ CTR_CDN_OBD : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" IBOX,TCU + +BO_ 1350 DI_BOX12: 8 DI_BOX + SG_ CF_DiBox_FrtInjVDiagReg0 : 0|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg0 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg1 : 32|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg2 : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CR_DiBox_BatVol : 48|8@1+ (0.1,0.0) [0.0|25.5] "V" EMS + SG_ CF_DiBox_SedInjVChg : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_FrtInjVChg : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_SedInjVErrSPI : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_FrtInjVErrSPI : 59|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 1349 EMS14: 8 EMS + SG_ IMMO_LAMP_STAT : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ L_MIL : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,IBOX + SG_ IM_STAT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ AMP_CAN : 3|5@1+ (10.731613,458.98) [458.98|791.660003] "mmHg" CLU,IBOX,TCU,TPMS + SG_ BAT_Alt_FR_Duty : 8|8@1+ (0.4,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ VB : 24|8@1+ (0.1015625,0.0) [0.0|25.8984375] "V" CLU,CUBIS,DATC,EPB,FPCM,IBOX + SG_ EMS_VS : 32|12@1+ (0.0625,0.0) [0.0|255.875] "km/h" CLU + SG_ TEMP_FUEL : 56|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" FPCM + +BO_ 68 DATC11: 8 DATC + SG_ CF_Datc_Type : 0|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Datc_VerMaj : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Datc_VerMin : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CR_Datc_OutTempC : 24|8@1+ (0.5,-41.0) [-41.0|86.5] "deg" CLU,FPCM + SG_ CR_Datc_OutTempF : 32|8@1+ (1.0,-42.0) [-42.0|213.0] "deg" CLU + SG_ CF_Datc_IncarTemp : 40|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" BCM,CLU + +BO_ 67 DATC13: 8 DATC + SG_ CF_Datc_TempDispUnit : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ CF_Datc_ModDisp : 2|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_IonClean : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_ChgReqDisp : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_IntakeDisp : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AutoDisp : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_FrDefLed : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ CF_Datc_AutoDefogBlink : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_ClmScanDisp : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AqsDisp : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AcDisp : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_OpSts : 25|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Mtc_MaxAcDisp : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_DualDisp : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_PwrInf : 32|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_RearManual : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearAutoDisp : 40|2@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Datc_RearOffDisp : 42|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearClimateScnDisp : 44|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearChgReqDisp : 46|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearModDisp : 48|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_RearBlwDisp : 52|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_PSModDisp : 56|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_FrontBlwDisp : 60|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX + +BO_ 66 DATC12: 8 DATC + SG_ CR_Datc_DrTempDispC : 0|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU,IBOX + SG_ CR_Datc_DrTempDispF : 8|8@1+ (1.0,56.0) [58.0|90.0] "¢µ" CLU,IBOX + SG_ CR_Datc_PsTempDispC : 16|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU,IBOX + SG_ CR_Datc_PsTempDispF : 24|8@1+ (1.0,56.0) [58.0|90.0] "¢µ" CLU,IBOX + SG_ CR_Datc_RearDrTempDispC : 40|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU + SG_ CR_Datc_RearDrTempDispF : 48|8@1+ (1.0,58.0) [58.0|90.0] "¢µ" CLU + SG_ CF_Datc_CO2_Warning : 56|8@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1345 CGW1: 8 BCM + SG_ CF_Gway_IGNSw : 0|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC + SG_ CF_Gway_RKECmd : 3|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyLockSw : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyUnlockSw : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvDrSw : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU + SG_ CF_Gway_DrvSeatBeltSw : 10|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,ESC,IBOX,PSB,TCU,EMS,EPB,ESC,IBOX,PSB,TCU + SG_ CF_Gway_TrunkTgSw : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ECS,EMS,EPB,ESC,IBOX,ECS,EMS,EPB,ESC,IBOX + SG_ CF_Gway_AstSeatBeltSw : 14|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,PSB,IBOX,PSB + SG_ CF_Gway_SMKOption : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_HoodSw : 17|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,EPB,ESC,IBOX,EMS,EPB,ESC,IBOX + SG_ CF_Gway_TurnSigLh : 19|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + SG_ CF_Gway_WiperIntT : 21|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperIntSw : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperLowSw : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperHighSw : 26|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperAutoSw : 27|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_RainSnsState : 28|3@1+ (1.0,0.0) [0.0|7.0] "" AFLS,EMS,IBOX,LDWS_LKAS,AFLS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_HeadLampLow : 31|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,SNV,AFLS,EMS,IBOX,LDWS_LKAS,SNV + SG_ CF_Gway_HeadLampHigh : 32|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,AFLS,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_HazardSw : 33|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS,ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS + SG_ CF_Gway_AstDrSw : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,IBOX + SG_ CF_Gway_DefoggerRly : 36|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX,EMS,IBOX + SG_ CF_Gway_ALightStat : 37|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_LightSwState : 38|2@1+ (1.0,0.0) [0.0|3.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_Frt_Fog_Act : 40|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigRHSw : 41|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigLHSw : 42|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_DriveTypeOption : 43|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_StarterRlyState : 44|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_PassiveAccessLock : 45|2@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_WiperMistSw : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_PassiveAccessUnlock : 48|2@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_RrSunRoofOpenState : 50|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,DATC,IBOX + SG_ CF_Gway_PassingSW : 51|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_HBAControlMode : 52|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_HLpHighSw : 53|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_InhibitRMT : 54|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,MDPS,PGS,SCC,SPAS,TPMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,PGS,SCC,SPAS,TPMS + SG_ CF_Gway_RainSnsOption : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SunRoofOpenState : 57|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,DATC,IBOX,DATC,IBOX + SG_ CF_Gway_Ign1 : 58|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_Ign2 : 59|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_ParkBrakeSw : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IBOX,SCC,ESC,IBOX,SCC + SG_ CF_Gway_TurnSigRh : 62|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + +BO_ 64 DATC14: 8 DATC + SG_ CF_Datc_AqsLevelOut : 0|4@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_DiagMode : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CR_Datc_SelfDiagCode : 8|8@1+ (1.0,-1.0) [0.0|254.0] "" CLU + SG_ DATC_SyncDisp : 16|4@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_OffDisp : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_SmartVentDisp : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_SmartVentOnOffStatus : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_AutoDefogSysOff_Disp : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_ADSDisp : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 832 LKAS11: 8 LDWS_LKAS + SG_ CF_Lkas_Icon : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX,PSB + SG_ CF_Lkas_LdwsSysState : 2|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX,PSB + SG_ CF_Lkas_SysWarning : 6|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Lkas_LdwsLHWarning : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,PSB + SG_ CF_Lkas_LdwsRHWarning : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,PSB + SG_ CF_Lkas_HbaLamp : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Lkas_FcwBasReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC + SG_ CR_Lkas_StrToqReq : 16|11@1+ (1.0,-1024.0) [-1024.0|1024.0] "" MDPS + SG_ CF_Lkas_ActToi : 27|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Lkas_ToiFlt : 28|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Lkas_HbaSysState : 29|3@1+ (1.0,0.0) [0.0|7.0] "" BCM,CLU + SG_ CF_Lkas_FcwOpt : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_HbaOpt : 34|2@1+ (1.0,0.0) [0.0|1.0] "" BCM,CGW + SG_ CF_Lkas_MsgCount : 36|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,MDPS + SG_ CF_Lkas_FcwSysState : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Lkas_FcwCollisionWarning : 43|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_FusionState : 45|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Lkas_Chksum : 48|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Lkas_FcwOpt_USM : 56|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Lkas_LdwsOpt_USM : 59|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,MDPS + +BO_ 1342 LKAS12: 6 LDWS_LKAS + SG_ CF_Lkas_TsrSlifOpt : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_LkasTsrStatus : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_TsrSpeed_Display_Clu : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_LkasTsrSpeed_Display_Navi : 24|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_Lkas_TsrAddinfo_Display : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1338 TMU_GW_E_01: 8 CLU + SG_ CF_Gway_TeleReqDrLock : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqDrUnlock : 2|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqHazard : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqHorn : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqEngineOperate : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1078 PAS11: 4 BCM + SG_ CF_Gway_PASDisplayFLH : 0|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayFRH : 3|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASRsound : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASDisplayFCTR : 8|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayRCTR : 11|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASFsound : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASDisplayRLH : 16|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASDisplayRRH : 19|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASCheckSound : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASSystemOn : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASOption : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PASDistance : 28|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 48 EMS18: 6 EMS + SG_ CF_Ems_DC1NumPerMSV : 0|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_DC2NumPerMSV : 8|16@1+ (1.0,0.0) [0.0|65535.0] "" DI_BOX + SG_ CR_Ems_DutyCyc1MSV : 24|8@1+ (0.1953,0.0) [0.0|49.8] "%" DI_BOX + SG_ CR_Ems_DutyCyc2MSV : 32|8@1+ (0.13725,0.0) [0.0|35.0] "%" DI_BOX + SG_ CR_Ems_DutyCyc3MSV : 40|8@1+ (0.392,0.0) [0.0|100.0] "%" DI_BOX + +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_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 + SG_ CF_Clu_HudBrightDnSW : 24|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudHeightUpSW : 26|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudHeightDnSW : 28|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudSet : 30|1@1+ (1.0,0.0) [0.0|1.0] "" HUD + SG_ CF_Clu_HudFontSizeSet : 31|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_LanguageInfo : 33|5@1+ (1.0,0.0) [0.0|31.0] "" BCM,PGS + SG_ CF_Clu_ClusterSound : 38|1@1- (1.0,0.0) [0.0|0.0] "" BCM,CGW,FATC + +BO_ 1066 _4WD13: 6 _4WD + SG_ _4WD_CURRENT : 0|8@1+ (0.390625,0.0) [-50.0|50.0] "A" TCU + SG_ _4WD_POSITION : 8|16@1+ (0.015625,0.0) [-180.0|180.0] "Deg" TCU + SG_ _4WD_CLU_THERM_STR : 24|8@1+ (1.0,0.0) [0.0|100.0] "%" TCU + SG_ _4WD_STATUS : 32|8@1+ (1.0,0.0) [0.0|15.0] "" ESC,TCU + +BO_ 1065 _4WD12: 8 _4WD + SG_ Ster_Pos : 0|16@1+ (1.0,-600.0) [-600.0|600.0] "Deg" ESC + SG_ FRSS : 16|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ FLSS : 24|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ RRSS : 32|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ RLSS : 40|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ CLU_PRES : 48|16@1+ (0.0625,-50.0) [-50.0|50.0] "Bar" ESC + +BO_ 809 EMS12: 8 EMS + SG_ CONF_TCU m1 : 0|6@1+ (1.0,0.0) [0.0|63.0] "" _4WD,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LCA,SMK + SG_ CAN_VERS m0 : 0|6@1+ (1.0,0.0) [0.0|7.7] "" _4WD,ABS,ESC,IBOX + SG_ TQ_STND m3 : 0|6@1+ (10.0,0.0) [0.0|630.0] "Nm" _4WD,DATC,ECS,EPB,ESC,FATC,IBOX + SG_ OBD_FRF_ACK m2 : 0|6@1+ (1.0,0.0) [0.0|63.0] "" _4WD,ESC,IBOX + SG_ MUL_CODE M : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ABS,ACU,BCM,CLU,DATC,ECS,EPB,ESC,IBOX,LCA,SMK,TCU + SG_ TEMP_ENG : 8|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" _4WD,BCM,CLU,DATC,EPB,ESC,IBOX,SMK,TCU + SG_ MAF_FAC_ALTI_MMV : 16|8@1+ (0.00781,0.0) [0.0|1.99155] "" IBOX,TCU + SG_ VB_OFF_ACT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ACK_ES : 25|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,IBOX + SG_ CONF_MIL_FMY : 26|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,IBOX,TCU + SG_ OD_OFF_REQ : 29|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ACC_ACT : 30|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ABS,CLU,ESC,IAP,IBOX,SCC,TCU + SG_ CLU_ACK : 31|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EPB,ESC,IBOX + SG_ BRAKE_ACT : 32|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ABS,ACU,AFLS,CLU,DATC,ECS,EPB,ESC,IBOX,LDWS_LKAS,TCU + SG_ ENG_CHR : 34|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,ABS,ACU,CLU,DATC,EPB,ESC,FATC,IBOX,SCC,SMK,TCU + SG_ GP_CTL : 38|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ TPS : 40|8@1+ (0.4694836,-15.0234742) [-15.0234742|104.6948357] "%" _4WD,ABS,ACU,CLU,DATC,ECS,EPB,ESC,IBOX,TCU + SG_ PV_AV_CAN : 48|8@1+ (0.3906,0.0) [0.0|99.603] "%" _4WD,AAF,ABS,ACU,AFLS,CLU,DATC,EPB,ESC,IAP,IBOX,LDWS_LKAS,SCC,TCU + SG_ ENG_VOL : 56|8@1+ (0.1,0.0) [0.0|25.5] "liter" _4WD,ABS,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,SCC,SMK + +BO_ 1064 _4WD11: 8 _4WD + SG_ _4WD_TYPE : 0|2@1+ (1.0,0.0) [0.0|3.0] "" ACU,ESC,TPMS + SG_ _4WD_SUPPORT : 2|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,ESC,TPMS + SG_ _4WD_ERR : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,ESC + SG_ CLU_DUTY : 16|8@1+ (1.0,0.0) [0.0|64.0] "%" ABS,ESC + SG_ R_TIRE : 24|8@1+ (1.0,200.0) [200.0|455.0] "mm" ABS,ESC,TPMS + SG_ _4WD_SW : 32|8@1+ (1.0,0.0) [0.0|9.9] "" ESC + SG_ _2H_ACT : 40|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC + SG_ _4H_ACT : 41|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,CLU,ESC,TPMS + SG_ LOW_ACT : 42|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,TCU,TPMS + SG_ AUTO_ACT : 43|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,TPMS + SG_ LOCK_ACT : 44|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,CLU,ESC,TPMS + SG_ _4WD_TQC_CUR : 48|16@1+ (1.0,0.0) [0.0|65535.0] "Nm" ABS,ESC + +BO_ 1319 HU_GW_E_01: 8 CLU + SG_ C_ADrLNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ C_ADrUNValueSet : 4|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ C_TwUnNValueSet : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_ABuzzerNValueSet : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_ArmWKeyNValueSet : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_PSMNValueSet : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SCMNValueSet : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_HLEscortNValueSet : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_WELNValueSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TriTurnLNValueSet : 22|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SNVWarnNValueSet : 24|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_LkasWarnNValueSet : 26|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1318 HU_GW_E_00: 8 CLU + SG_ C_ADrLURValueReq : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TwUnRValueReq : 2|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_AlarmRValueReq : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_IMSRValueReq : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_HLEscortRValueReq : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_WELRValueReq : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TriTurnLRValueReq : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SNVWarnRValueReq : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_LkasWarnRValueReq : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1317 GW_HU_E_01: 8 BCM + SG_ C_ADrLRValue : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_ADrURValue : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_TwUnRValue : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ABuzzerRValue : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ArmWKeyRValue : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_PSMRValue : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SCMRValue : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_HLEscortRValue : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_WELRValue : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TriTurnLRValue : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1316 GW_HU_E_00: 8 BCM + SG_ C_ADrLUNValueConf : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TwUnNValueConf : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_AlarmNValueConf : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_PSMNValueConf : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SCMNValueConf : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_HLEscortNValueConf : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_WELNValueConf : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TriTurnLNValueConf : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1315 GW_SWRC_PE: 8 BCM + SG_ C_ModeSW : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_MuteSW : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SeekDnSW : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SeekUpSW : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_BTPhoneCallSW : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_BTPhoneHangUpSW : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_DISCDownSW : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_DISCUpSW : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SdsSW : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_MTSSW : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_VolDnSW : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_VolUpSW : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1314 GW_IPM_PE_1: 8 BCM + SG_ C_AV_Tail : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ParkingBrakeSW : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_RKECMD : 4|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ C_BAState : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_IGNSW : 12|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_CountryCfg : 16|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_TailLampActivity : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ RearSW_RSELockOnOff : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SMKTeleCrankingState : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SMKTeleCrankingFailRes : 34|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1057 SCC12: 8 SCC + SG_ CF_VSM_Prefill : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_VSM_DecCmdAct : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_VSM_HBACmd : 2|2@1+ (1.0,0.0) [0.0|3.0] "" ESC + SG_ CF_VSM_Warn : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IAP + SG_ CF_VSM_Stat : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,PSB + SG_ CF_VSM_BeltCmd : 8|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,PSB + SG_ ACCFailInfo : 11|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,ESC,IBOX + SG_ ACCMode : 13|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IBOX,TCU + SG_ StopReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EPB,ESC + SG_ CR_VSM_DecCmd : 16|8@1+ (0.01,0.0) [0.0|2.55] "g" ESC + SG_ aReqMax : 24|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ TakeOverReq : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC,TCU + SG_ PreFill : 36|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,TCU + SG_ aReqMin : 37|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ CF_VSM_ConfMode : 48|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_Failinfo : 50|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_Status : 52|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_CmdAct : 54|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ AEB_StopReq : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC + SG_ CR_VSM_Alive : 56|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,PSB + SG_ CR_VSM_ChkSum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,PSB + +BO_ 1313 GW_DDM_PE: 8 BCM + SG_ C_DRVDoorStatus : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ASTDoorStatus : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_RLDoorStatus : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + 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.0) [0.0|1.0] "" CLU,EMS,ESC + SG_ SCCInfoDisplay : 1|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC + SG_ AliveCounterACC : 4|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,EMS,ESC,TCU + SG_ VSetDis : 8|8@1+ (1.0,0.0) [0.0|255.0] "km/h or MPH" CLU,ESC,TCU + SG_ ObjValid : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC,TCU + SG_ DriverAlertDisplay : 17|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ TauGapSet : 19|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC,TCU + SG_ ACC_ObjStatus : 22|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,ESC + SG_ ACC_ObjLatPos : 24|9@1+ (0.1,-20.0) [-20.0|31.1] "m" ABS,ESC + SG_ ACC_ObjDist : 33|11@1+ (0.1,0.0) [0.0|204.7] "m" ABS,ESC + SG_ ACC_ObjRelSpd : 44|12@1+ (0.1,-170.0) [-170.0|239.5] "m/s" ABS,ESC + SG_ Navi_SCC_Curve_Status : 56|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Curve_Act : 58|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Camera_Act : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Camera_Status : 62|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1312 CGW3: 8 BCM + SG_ CR_Photosensor_LH : 0|8@1+ (78.125,0.0) [0.0|20000.0] "" DATC,DATC + SG_ CR_Photosensor_RH : 10|8@1+ (78.125,0.0) [0.0|20000.0] "" DATC,DATC + SG_ CF_Hoodsw_memory : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EMS + SG_ C_MirOutTempSns : 24|8@1+ (0.5,-40.5) [-40.0|60.0] "deg" AAF,CLU,DATC,EMS,SPAS,AAF,DATC,EMS,SPAS + +BO_ 544 ESP12: 8 ESC + SG_ LAT_ACCEL : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_STAT : 11|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_DIAG : 12|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LONG_ACCEL : 13|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_DIAG : 25|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ CYL_PRES : 26|12@1+ (0.1,0.0) [0.0|409.5] "Bar" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRES_STAT : 38|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRESS_DIAG : 39|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EMS,EPB,IBOX,PSB,SCC,TCU + SG_ YAW_RATE : 40|13@1+ (0.01,-40.95) [-40.95|40.96] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_STAT : 53|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_DIAG : 54|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ ESP12_AliveCounter : 56|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ ESP12_Checksum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1307 CLU16: 8 CLU + SG_ CF_Clu_TirePressUnitNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" TPMS + SG_ CF_Clu_SlifNValueSet : 3|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_RearWiperNValueSet : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 790 EMS11: 8 EMS + SG_ SWI_IGK : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ABS,ACU,AHLS,CUBIS,DI_BOX,ECS,EPB,ESC,IBOX,LDWS_LKAS,MDPS,REA,SAS,SCC,TCU + SG_ F_N_ENG : 1|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,IBOX,MDPS,SCC,TCU + SG_ ACK_TCS : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ PUC_STAT : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,DATC,IBOX,TCU + SG_ TQ_COR_STAT : 4|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ESC,IBOX,TCU + SG_ RLY_AC : 6|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,IBOX,TCU + SG_ F_SUB_TQI : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQI_ACOR : 8|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ N : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,FPCM,IBOX,MDPS,SCC,TCU + SG_ TQI : 32|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ VS : 48|8@1+ (1.0,0.0) [0.0|254.0] "km/h" _4WD,AAF,ACU,AHLS,BCM,CLU,DATC,ECS,EPB,IBOX,LCA,LDWS_LKAS,LVR,MDPS,ODS,SCC,SMK,SPAS,TCU,TPMS + SG_ RATIO_TQI_BAS_MAX_STND : 56|8@1+ (0.0078,0.0) [0.0|2.0] "" _4WD,IBOX,TCU + +BO_ 1301 CLU14: 8 CLU + SG_ CF_Clu_ADrUNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_ADrLNValueSet : 3|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_EscortHLNValueSet : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_DoorLSNValueSet : 8|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_PSMNValueSet : 11|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_TTUnlockNValueSet : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_PTGMNValueSet : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_SCMNValueSet : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_WlightNValueSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_TempUnitNValueSet : 22|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,DATC + SG_ CF_Clu_MoodLpNValueSet : 24|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_TrfChgSet : 27|2@1+ (1.0,0.0) [0.0|3.0] "" AFLS + SG_ CF_Clu_OTTurnNValueSet : 29|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_LcaNValueSet : 32|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_RctaNValueSet : 34|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_RcwNValueSet : 36|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_EscOffNValueSet : 38|3@1+ (1.0,0.0) [0.0|7.0] "" ESC + SG_ CF_Clu_SccNaviCrvNValueSet : 41|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_SccNaviCamNValueSet : 43|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_SccAebNValueSet : 45|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_LkasModeNValueSet : 47|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_FcwNValueSet : 51|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_PasSpkrLvNValueSet : 53|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_SccDrvModeNValueSet : 56|3@1+ (1.0,0.0) [0.0|7.0] "" SCC + SG_ CF_Clu_HAnBNValueSet : 59|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_HfreeTrunkTgNValueSet : 61|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + +BO_ 275 TCU13: 8 TCU + SG_ N_TGT_LUP : 0|8@1+ (10.0,500.0) [500.0|3040.0] "rpm" EMS,IBOX + SG_ SLOPE_TCU : 8|6@1+ (0.5,-16.0) [-16.0|15.5] "%" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhCda : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_IsgInhib : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_BkeOnReq : 16|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_NCStat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_TarGr : 20|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,CLU,DATC,EMS,EPB,ESC,IBOX,SCC + SG_ CF_Tcu_ShfPatt : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhVis : 28|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_PRelReq : 29|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LVR + SG_ CF_Tcu_ITPhase : 30|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_ActEcoRdy : 31|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_TqGrdLim : 32|8@1+ (10.0,0.0) [0.0|2540.0] "Nm/s" EMS,IBOX + SG_ CR_Tcu_IsgTgtRPM : 40|8@1+ (20.0,0.0) [0.0|3500.0] "rpm" EMS,IBOX + SG_ CF_Tcu_SptRdy : 48|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Tcu_SbwPInfo : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_Alive3 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_ChkSum3 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + +BO_ 274 TCU12: 8 TCU + SG_ ETL_TCU : 0|8@1+ (2.0,0.0) [0.0|508.0] "Nm" EMS,IBOX + SG_ CUR_GR : 8|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,ESC,IBOX,SCC,TPMS + SG_ CF_Tcu_Alive : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX,SCC + SG_ CF_Tcu_ChkSum : 14|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX,SCC + SG_ VS_TCU : 16|8@1+ (1.0,0.0) [0.0|254.0] "km/h" BCM,CLU,DATC,EMS,IBOX,LCA,LVR,PGS,SMK,SNV + SG_ FUEL_CUT_TCU : 28|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ INH_FUEL_CUT : 29|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ IDLE_UP_TCU : 30|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ N_INC_TCU : 31|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15.0|15.0] "" EMS,IBOX + SG_ N_TC_RAW : 40|16@1+ (0.25,0.0) [0.0|16383.5] "rpm" EMS,IBOX + SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0.0) [0.0|0.9921875] "km/h" CLU,EMS,IBOX,LCA + +BO_ 273 TCU11: 8 TCU + SG_ TQI_TCU_INC : 0|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,ESC,IBOX + SG_ G_SEL_DISP : 8|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,AFLS,AVM,BCM,CGW,CLU,CUBIS,ECS,EMS,EPB,ESC,IAP,IBOX,LCA,LDWS_LKAS,LVR,MDPS,PGS,SCC,SMK,SNV,SPAS,TPMS + SG_ F_TCU : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX + SG_ TCU_TYPE : 14|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,EMS,ESC,IBOX + SG_ TCU_OBD : 16|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,ESC,IBOX + SG_ SWI_GS : 19|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,ESC,IBOX,SCC + SG_ GEAR_TYPE : 20|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,CLU,EMS,ESC,IBOX,SCC + SG_ TQI_TCU : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,ESC,IBOX + SG_ TEMP_AT : 32|8@1+ (1.0,-40.0) [-40.0|214.0] "deg" AAF,CLU,CUBIS,EMS,ESC,IBOX + SG_ N_TC : 40|16@1+ (0.25,0.0) [0.0|16383.5] "rpm" _4WD,EMS,EPB,ESC,IBOX + SG_ SWI_CC : 56|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,CLU,EMS,ESC,IBOX + SG_ CF_Tcu_Alive1 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_ChkSum1 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + +BO_ 16 ACU13: 8 ACU + SG_ CF_Acu_CshAct : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CUBIS,IBOX,ODS + +BO_ 1040 CGW_USM1: 8 BCM + SG_ CF_Gway_ATTurnRValue : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PTGMRValue : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_EscortHLRValue : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_TTUnlockRValue : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_ADrLRValue : 8|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_ADrURValue : 11|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_SCMRValue : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_WlightRValue : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PSMRValue : 18|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_OTTurnRValue : 21|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_DrLockSoundRValue : 24|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_HAnBRValue : 27|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_MoodLpRValue : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_HfreeTrunkRValue : 32|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_AutoLightRValue : 35|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_RearWiperRValue : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PasSpkrLvRValue : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + +BO_ 1292 CLU13: 8 CLU + SG_ CF_Clu_LowfuelWarn : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,FPCM,IBOX + SG_ CF_Clu_RefDetMod : 2|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX + SG_ CF_Clu_AvgFCU : 3|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ CF_Clu_AvsmCur : 5|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,SCC + SG_ CF_Clu_AvgFCI : 6|10@1+ (0.1,0.0) [0.0|102.2] "" IBOX + SG_ CF_Clu_DrivingModeSwi : 16|2@1+ (1.0,0.0) [0.0|3.0] "" DATC,ECS,EMS,ESC,IAP,MDPS,TCU + SG_ CF_Clu_FuelDispLvl : 18|5@1+ (1.0,0.0) [0.0|31.0] "" CGW,IBOX + SG_ CF_Clu_FlexSteerSW : 23|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Clu_DTE : 24|10@1+ (1.0,0.0) [0.0|1023.0] "" DATC + SG_ CF_Clu_TripUnit : 34|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ CF_Clu_SWL_Stat : 36|3@1+ (1.0,0.0) [0.0|7.0] "" ACU,EMS + SG_ CF_Clu_ActiveEcoSW : 39|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,EMS,TCU + SG_ CF_Clu_EcoDriveInf : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CUBIS,EMS,IAP,IBOX + SG_ CF_Clu_IsaMainSW : 43|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Clu_LdwsLkasSW : 56|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Clu_AltLStatus : 59|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,DATC,EMS + SG_ CF_Clu_AliveCnt2 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,LDWS_LKAS + +BO_ 1290 SCC13: 8 SCC + SG_ SCCDrvModeRValue : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ SCC_Equip : 3|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ AebDrvSetStatus : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC + +BO_ 1287 TCS15: 4 ESC + SG_ ABS_W_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,CUBIS,IBOX + SG_ TCS_OFF_LAMP : 1|2@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,CLU + SG_ TCS_LAMP : 3|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ACU,CLU,CUBIS,IBOX,SCC + SG_ DBC_W_LAMP : 5|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ DBC_F_LAMP : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,CLU + SG_ ESC_Off_Step : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ AVH_CLU : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,EPB + SG_ AVH_I_LAMP : 24|2@1+ (1.0,0.0) [0.0|3.0] "" EPB + SG_ EBD_W_LAMP : 26|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ AVH_ALARM : 27|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ AVH_LAMP : 29|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EPB,SPAS + +BO_ 1282 TCU14: 4 TCU + SG_ CF_TCU_WarnMsg : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_TCU_WarnImg : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_TCU_WarnSnd : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Tcu_GSel_BlinkReq : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,LVR + SG_ CF_Tcu_StRelStat : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn1 : 13|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn2 : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,ESC + +BO_ 1281 ECS11: 3 ECS + SG_ ECS_W_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,IBOX + SG_ SYS_NA : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ ECS_DEF : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ ECS_DIAG : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ L_CHG_NA : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Leveling_Off : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ LC_overheat : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Lifting : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Lowering : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Damping_Mode : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_Damping : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_Height : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_level : 16|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ ACT_Height : 20|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + +BO_ 1024 CLU_CFG11: 2 CLU + SG_ Vehicle_Type : 0|16@1+ (1.0,0.0) [0.0|65536.0] "" _4WD + +BO_ 1280 ACU14: 1 ACU + SG_ CF_SWL_Ind : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_TTL_Ind : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_SBR_Ind : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + +BO_ 512 EMS20: 6 EMS + SG_ FCO : 0|16@1+ (0.128,0.0) [0.0|8388.48] "ul" CLU,CUBIS,FPCM,IBOX + SG_ CF_Ems_PumpTPres : 16|8@1+ (3.137254902,0.0) [0.0|800.0] "kPa" FPCM,IBOX + SG_ Split_Stat : 32|1@1+ (1.0,0.0) [0.0|1.0] "" FPCM diff --git a/opendbc/kia_sorento_2018.dbc b/opendbc/kia_sorento_2018.dbc new file mode 100644 index 00000000000000..919da4cc2dd90c --- /dev/null +++ b/opendbc/kia_sorento_2018.dbc @@ -0,0 +1,1391 @@ +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_: IAP ODS _4WD BCM HUD DATC MDPS AAF_Tester AEMC SMK _4WD EPB CUBIS MTS TMU EVP CGW TPMS LPI DI_BOX SPAS ACU Dummy AFLS CLU EMS AVM LDWS_LKAS SCC IBOX LCA PGS AHLS SAS AAF ECS ESC PSB TCU ABS REA FATC FPCM SNV LVR XXX + + +BO_ 1532 ODS13: 5 ODS + SG_ CR_Ods_ID : 0|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_Chksum_H : 8|8@1+ (1,0) [0|255] "" Dummy + SG_ CR_Ods_Chksum_L : 16|8@1+ (1,0) [0|255] "" Dummy + SG_ CR_Ods_RomID_H : 24|8@1+ (1,0) [0|255] "" Dummy + SG_ CR_Ods_RomID_L : 32|8@1+ (1,0) [0|255] "" Dummy + +BO_ 1531 ODS12: 8 ODS + SG_ CR_Ods_SerNum0 : 0|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_SerNum1 : 8|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_SerNum2 : 16|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_SerNum3 : 24|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_SerNum4 : 32|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_SerNum5 : 40|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_SerNum6 : 48|8@1+ (1,0) [0|255] "" ACU + SG_ CR_Ods_SerNum7 : 56|8@1+ (1,0) [0|255] "" ACU + +BO_ 1530 ODS11: 8 ODS + SG_ CF_Ods_PrcCmd : 1|1@1+ (1,0) [0|1] "" Dummy + SG_ CF_Ods_BtsFail : 3|1@1+ (1,0) [0|1] "" Dummy + SG_ CF_Ods_AcuRcvSN : 4|1@1+ (1,0) [0|1] "" ACU + SG_ CF_Ods_EolCal : 5|1@1+ (1,0) [0|1] "" ACU + SG_ CF_Ods_PsFail : 6|1@1+ (1,0) [0|1] "" ACU + SG_ CF_Ods_EcuFail : 7|1@1+ (1,0) [0|1] "" ACU + SG_ CF_Ods_WgtStat : 8|1@1+ (1,0) [0|1] "" ACU + SG_ CF_Ods_OccStat : 16|1@1+ (1,0) [0|1] "" ACU + SG_ CR_Wcs_ErrStat : 32|8@1+ (1,0) [0|63] "" ACU + SG_ CR_Wcs_ClassStat : 40|8@1+ (1,0) [0|4] "" ACU,BCM + +BO_ 1017 ECS12: 4 ECS + SG_ Height_FL : 0|8@1+ (1,-128) [-128|127] "mm" AFLS + SG_ Height_FR : 8|8@1+ (1,-128) [-128|127] "mm" AFLS + SG_ Height_RL : 16|8@1+ (1,-128) [-128|127] "mm" AFLS + SG_ Height_RR : 24|8@1+ (1,-128) [-128|127] "mm" AFLS + +BO_ 1268 SPAS12: 8 SPAS + SG_ CF_Spas_HMI_Stat : 0|8@1+ (1,0) [0|255] "" CLU + SG_ CF_Spas_Disp : 8|2@1+ (1,0) [0|3] "" CLU,EMS + SG_ CF_Spas_FIL_Ind : 10|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_FIR_Ind : 13|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_FOL_Ind : 16|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_FOR_Ind : 19|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_VolDown : 22|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Spas_RIL_Ind : 24|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_RIR_Ind : 27|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_FLS_Alarm : 30|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Spas_ROL_Ind : 32|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_ROR_Ind : 35|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_FCS_Alarm : 38|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Spas_FI_Ind : 40|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_RI_Ind : 43|3@1+ (1,0) [0|7] "" AVM,CLU + SG_ CF_Spas_FRS_Alarm : 46|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Spas_FR_Alarm : 48|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_Spas_RR_Alarm : 50|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_Spas_BEEP_Alarm : 52|4@1+ (1,0) [0|15] "" BCM,CLU + SG_ CF_Spas_StatAlarm : 56|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Spas_RLS_Alarm : 57|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Spas_RCS_Alarm : 59|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Spas_RRS_Alarm : 61|2@1+ (1,0) [0|3] "" CLU + +BO_ 1265 CLU11: 4 CLU + SG_ CF_Clu_CruiseSwState : 0|3@1+ (1,0) [0|7] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_CruiseSwMain : 3|1@1+ (1,0) [0|1] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_SldMainSW : 4|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Clu_ParityBit1 : 5|1@1+ (1,0) [0|1] "pulse count" EMS + SG_ CF_Clu_VanzDecimal : 6|2@1+ (0.125,0) [0|0.375] "" EMS + SG_ CF_Clu_Vanz : 8|9@1+ (0.5,0) [0|255.5] "km/h or MPH" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_SPEED_UNIT : 17|1@1+ (1,0) [0|1] "" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_DetentOut : 18|1@1+ (1,0) [0|1] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_RheostatLevel : 19|5@1+ (1,0) [0|31] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_CluInfo : 24|1@1+ (1,0) [0|1] "" BCM + SG_ CF_Clu_AmpInfo : 25|1@1+ (1,0) [0|1] "" BCM + SG_ CF_Clu_AliveCnt1 : 28|4@1+ (1,0) [0|15] "" AHLS,EMS,EPB,LDWS_LKAS,MDPS,SCC + +BO_ 1492 TMU_GW_PE_01: 8 CLU + SG_ TMU_IVRActivity : 0|2@1+ (1,0) [0|3] "" DATC + SG_ TMU_PhoneActivity : 2|2@1+ (1,0) [0|3] "" DATC + +BO_ 1491 HU_DATC_PE_00: 8 CLU + SG_ HU_VRActivity : 0|2@1+ (1,0) [0|3] "" DATC + SG_ HU_PhoneActivity : 2|2@1+ (1,0) [0|3] "" DATC + SG_ BlowerNoiseControl : 4|2@1+ (1,0) [0|3] "" DATC + +BO_ 1490 HU_DATC_E_02: 8 CLU + SG_ HU_DATC_RearOnOffSet : 6|2@1+ (1,0) [0|3] "" DATC + SG_ HU_DATC_ADSOnOffSet : 8|2@1+ (1,0) [0|3] "" DATC + +BO_ 1479 EMS21: 8 EMS + SG_ SCR_LEVEL_WARN_LAMP : 0|1@1+ (1,0) [0|1] "" CLU + SG_ SCR_LEVEL_WARN : 1|3@1+ (1,0) [0|4] "" CLU + SG_ SCR_SYS_ERROR_WARN : 4|3@1+ (1,0) [0|7] "" CLU + SG_ SCR_SYSTEM_WARN_LAMP : 7|1@1+ (1,0) [0|1] "" CLU + SG_ SCR_INDUCEMENT_EXIT_COND : 8|2@1+ (1,0) [0|3] "" CLU + SG_ SCR_UREA_LEVEL : 16|8@1+ (0.5,0) [0|100] "%" CLU + SG_ SCR_NO_REMAINING_RESTARTS : 24|8@1+ (1,0) [0|255] "" CLU + SG_ SCR_REMAINING_DISTANCE : 32|16@1+ (1,0) [0|25000] "km" CLU + +BO_ 1472 GW_Warning_PE: 8 BCM + SG_ Audio_VolumeDown : 38|2@1+ (1,0) [0|3] "" CLU + SG_ Pas_Spkr_Flh_Alarm : 48|2@1+ (1,0) [0|3] "" CLU + SG_ Pas_Spkr_Fcnt_Alarm : 50|2@1+ (1,0) [0|3] "" CLU + SG_ Pas_Spkr_Frh_Alarm : 52|2@1+ (1,0) [0|3] "" CLU + SG_ Pas_Spkr_Rlh_Alarm : 56|2@1+ (1,0) [0|3] "" CLU,PGS + SG_ Pas_Spkr_Rcnt_Alarm : 58|2@1+ (1,0) [0|3] "" CLU + SG_ Pas_Spkr_Rrh_Alarm : 60|2@1+ (1,0) [0|3] "" CLU,PGS + +BO_ 1984 CAL_SAS11: 2 ESC + SG_ CCW : 0|4@1+ (1,0) [0|15] "" SAS + SG_ SAS_CID : 4|11@1+ (1,0) [0|2047] "" SAS + +BO_ 1456 CLU12: 4 CLU + SG_ CF_Clu_Odometer : 0|24@1+ (0.1,0) [0|1677721.4] "km" _4WD,AAF,BCM,CUBIS,EMS,EPB,IBOX,LDWS_LKAS,SCC,TPMS + +BO_ 688 SAS11: 5 MDPS + SG_ SAS_Angle : 0|16@1- (0.1,0) [-3276.8|3276.7] "Deg" _4WD,ACU,AFLS,AVM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU,_4WD,ACU,AFLS,AVM,BCM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU + SG_ SAS_Speed : 16|8@1- (4,0) [0|1016] "" AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU,AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU + SG_ SAS_Stat : 24|8@1+ (1,0) [0|255] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ MsgCount : 32|4@1+ (1,0) [0|15] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + SG_ CheckSum : 36|4@1+ (1,0) [0|15] "" ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + +BO_ 1441 ACU12: 8 ACU + SG_ CR_Acu_SN : 0|64@1+ (1,0) [0|0] "" ODS + +BO_ 1440 ACU11: 8 ACU + SG_ CF_Ods_SNRcv : 1|1@1+ (1,0) [0|1] "" ODS + SG_ CF_Ods_IDRcv : 2|1@1+ (1,0) [0|1] "" ODS + SG_ CF_Ods_RZReq : 4|1@1+ (1,0) [0|1] "" ODS + SG_ CF_Abg_DepInhEnt : 6|1@1+ (1,0) [0|1] "" ODS + SG_ CF_Abg_DepEnt : 7|1@1+ (1,0) [0|1] "" ODS + SG_ CF_PasBkl_FltStat : 28|1@1+ (1,0) [0|1] "" ODS,PSB + SG_ CF_DriBkl_FltStat : 29|1@1+ (1,0) [0|1] "" ODS,PSB + SG_ CF_PasBkl_Stat : 30|1@1+ (1,0) [0|1] "" IBOX,ODS,PSB,TMU + SG_ CF_DriBkl_Stat : 31|1@1+ (1,0) [0|1] "" ODS,PSB + SG_ CF_SWL_Ind : 32|2@1+ (1,0) [0|3] "" CUBIS,IBOX + SG_ CF_Acu_FltStat : 34|2@1+ (1,0) [0|3] "" CUBIS,IBOX + SG_ CF_Acu_ExtOfSab : 36|2@1+ (1,0) [0|3] "" BCM,CLU,CUBIS,IBOX + SG_ CF_Acu_Dtc : 40|16@1+ (1,0) [0|65535] "" CUBIS,IBOX + SG_ CF_Acu_NumOfFlt : 56|8@1+ (1,0) [0|255] "" CUBIS,IBOX + +BO_ 1437 AHLS11: 8 AHLS + SG_ CF_Ahls_WarnLamp : 0|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Ahls_WarnMsg : 2|2@1+ (1,0) [0|3] "" CLU + +BO_ 1434 PSB11: 2 PSB + SG_ PSB_LH_FAIL : 0|2@1+ (1,0) [0|3] "" CLU + SG_ PSB_LH_TGL : 2|1@1+ (1,0) [0|1] "" CLU + SG_ PSB_LH_ACT : 3|4@1+ (1,0) [0|4] "" Dummy + SG_ PSB_RH_FAIL : 8|2@1+ (1,0) [0|3] "" CLU + SG_ PSB_RH_TGL : 10|1@1+ (1,0) [0|1] "" CLU + SG_ PSB_RH_ACT : 11|4@1+ (1,0) [0|4] "" Dummy + +BO_ 916 TCS13: 8 ESC + SG_ aBasis : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ BrakeLight : 11|1@1+ (1,0) [0|1] "" CLU,EMS,SCC + SG_ DCEnable : 12|1@1+ (1,0) [0|1] "" EMS,SCC + SG_ AliveCounterTCS : 13|3@1+ (1,0) [0|7] "" EMS,SCC + SG_ ACCReqLim : 22|2@1+ (1,0) [0|3] "" EMS,SCC + SG_ TQI_ACC : 24|8@1+ (0.390625,0) [0|99.609375] "%" EMS + SG_ ACCEL_REF_ACC : 32|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ ACCEnable : 43|2@1+ (1,0) [0|3] "" EMS,SCC + SG_ DriverOverride : 45|2@1+ (1,0) [0|3] "" EMS,SCC + SG_ StandStill : 47|1@1+ (1,0) [0|1] "" EMS,SCC + SG_ CheckSum_TCS3 : 48|4@1+ (1,0) [0|15] "" EMS,SCC + SG_ ACC_EQUIP : 52|1@1+ (1,0) [0|1] "" EMS,SCC + SG_ PBRAKE_ACT : 53|1@1+ (1,0) [0|1] "" EMS,SCC + SG_ ACC_REQ : 54|1@1+ (1,0) [0|1] "" EMS + SG_ DriverBraking : 55|1@1+ (1,0) [0|1] "" EMS,SCC + SG_ CF_VSM_Coded : 56|1@1+ (1,0) [0|1] "" SCC + SG_ CF_VSM_Avail : 57|2@1+ (1,0) [0|3] "" CLU,SCC + SG_ CF_VSM_Handshake : 59|1@1+ (1,0) [0|1] "" SCC + SG_ CF_DriBkeStat : 60|1@1+ (1,0) [0|1] "" SCC + SG_ CF_VSM_ConfSwi : 61|2@1+ (1,0) [0|3] "" SCC + SG_ AEB_EQUIP : 63|1@1+ (1,0) [0|1] "" SCC + +BO_ 1427 TPMS11: 6 BCM + SG_ TPMS_W_LAMP : 0|2@1+ (1,0) [0|3] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ TREAD_W_LAMP : 2|2@1+ (1,0) [0|3] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ POS_FL_W_LAMP : 4|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX + SG_ POS_FR_W_LAMP : 5|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RL_W_LAMP : 6|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RR_W_LAMP : 7|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX + SG_ STATUS_TPMS : 8|3@1+ (1,0) [0|0] "" CLU + SG_ UNIT : 11|2@1+ (1,0) [0|3] "" CLU + SG_ PRESSURE_FL : 16|8@1+ (1,0) [0|255] "" CLU + SG_ PRESSURE_FR : 24|8@1+ (1,0) [0|255] "" CLU + SG_ PRESSURE_RL : 32|8@1+ (1,0) [0|255] "" CLU + SG_ PRESSURE_RR : 40|8@1+ (1,0) [0|255] "" CLU + +BO_ 915 TCS12: 4 ESC + SG_ SA_COUNT : 0|16@1+ (2,-32768) [-32768|98302] "" _4WD,ACU,MDPS + SG_ SA_Z_COUNT : 16|15@1+ (2,-32768) [-32768|32766] "" _4WD,ACU,MDPS + SG_ SA_Z_FLAG : 31|1@1+ (1,0) [0|1] "" _4WD,ACU,MDPS + +BO_ 1170 EMS19: 8 EMS + SG_ CF_Ems_BrkReq : 0|1@1+ (1,0) [0|1] "" ESC,IBOX,TCU + SG_ CF_Ems_DnShftReq : 1|4@1+ (1,0) [0|14] "" IBOX,TCU + SG_ CF_Ems_RepModChk : 5|2@1+ (1,0) [0|3] "" IBOX + SG_ CF_Ems_AAFOpenReq : 7|1@1+ (1,0) [0|1] "" AAF,IBOX + SG_ CF_Ems_DecelReq : 8|12@1+ (0.001,-4.094) [-4.094|0] "m/s^2" ESC,IBOX,TCU + SG_ CR_Ems_BstPre : 20|12@1+ (1.322,0) [0|4094] "hPa" CLU,IBOX + SG_ CR_Ems_EngOilTemp : 32|8@1+ (0.75,-40) [0|254] "deg" CLU,IBOX + SG_ DPF_LAMP_STAT : 40|2@1+ (1,0) [0|3] "" CLU,IBOX + SG_ BAT_LAMP_STAT : 42|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_ModeledAmbTemp : 48|8@1+ (0.5,-41) [-41|85.5] "deg" AAF,IBOX + SG_ CF_Ems_OPSFail : 56|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_AliveCounterEMS9 : 58|2@1+ (1,0) [0|3] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + SG_ CF_Ems_ChecksumEMS9 : 60|4@1+ (1,0) [0|15] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + +BO_ 1425 AFLS11: 2 AFLS + SG_ AFLS_STAT : 1|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Afls_TrfChgStat : 3|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Afls_LedHLStat : 4|2@1+ (1,0) [0|3] "" CLU + +BO_ 912 SPAS11: 7 SPAS + SG_ CF_Spas_Stat : 0|4@1+ (1,0) [0|15] "" ESC,MDPS + SG_ CF_Spas_TestMode : 4|2@1+ (1,0) [0|3] "" MDPS + SG_ CR_Spas_StrAngCmd : 8|16@1- (0.1,0) [-3276.8|3276.7] "" MDPS + SG_ CF_Spas_BeepAlarm : 24|4@1+ (1,0) [0|15] "" CLU + SG_ CF_Spas_Mode_Seq : 28|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Spas_AliveCnt : 32|8@1+ (1,0) [0|255] "" MDPS + SG_ CF_Spas_Chksum : 40|8@1+ (1,0) [0|255] "" MDPS + SG_ CF_Spas_PasVol : 48|3@1+ (1,0) [0|7] "" CGW,CLU + +BO_ 1168 EPB11: 7 EPB + SG_ EPB_I_LAMP : 0|4@1+ (1,0) [0|15] "" BCM,CLU,CUBIS,ESC,IBOX + SG_ EPB_F_LAMP : 4|2@1+ (1,0) [0|3] "" CLU,CUBIS,ESC,IBOX + SG_ EPB_ALARM : 6|2@1+ (1,0) [0|3] "" CLU,ESC + SG_ EPB_CLU : 8|8@1+ (1,0) [0|255] "" CLU,ESC + SG_ EPB_SWITCH : 16|2@1+ (1,0) [0|3] "" ESC,SCC + SG_ EPB_RBL : 18|1@1+ (1,0) [0|1] "" EMS,ESC + SG_ EPB_STATUS : 19|3@1+ (1,0) [0|7] "" CLU,EMS,ESC,SCC,TCU + SG_ EPB_FRC_ERR : 22|2@1+ (1,0) [0|3] "" EMS,ESC,SCC,TCU + SG_ EPB_DBF_STAT : 24|1@1+ (1,0) [0|1] "" ESC + SG_ ESP_ACK : 25|1@1+ (1,0) [0|1] "" ESC + SG_ EPB_DBF_REQ : 26|1@1+ (1,0) [0|1] "" ESC + SG_ EPB_FAIL : 29|3@1+ (1,0) [0|7] "" ESC,SCC + SG_ EPB_FORCE : 32|12@1+ (1,-1000) [-1000|3000] "" ESC + SG_ EPB_DBF_DECEL : 48|8@1+ (0.01,0) [0|2.54] "g" ESC + +BO_ 399 EMS_H12: 8 EMS + SG_ R_TqAcnApvC : 0|8@1+ (0.2,0) [0|51] "Nm" DATC,IBOX + SG_ R_PAcnC : 8|8@1+ (125,0) [0|31875] "hPa" DATC,IBOX + SG_ TQI_B : 16|8@1+ (0.390625,0) [0|99.609375] "%" ABS,ESC,IBOX + SG_ SLD_VS : 24|8@1+ (1,0) [0|255] "km/h" CLU,IBOX + SG_ CF_CdaStat : 32|3@1+ (1,0) [0|7] "" AEMC,IBOX,TCU + SG_ CF_Ems_IsgStat : 35|3@1+ (1,0) [0|7] "" ABS,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,MDPS,SMK,TCU + SG_ CF_Ems_OilChg : 38|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_EtcLimpMod : 39|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ R_NEngIdlTgC : 40|8@1+ (10,0) [0|2550] "rpm" DATC,IBOX,TCU + SG_ CF_Ems_UpTarGr : 48|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_DownTarGr : 49|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_DesCurGr : 50|4@1+ (1,0) [0|15] "" CLU,IBOX + SG_ CF_Ems_SldAct : 54|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_SldPosAct : 55|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_HPresStat : 56|1@1+ (1,0) [0|1] "" IBOX,TCU + SG_ CF_Ems_IsgBuz : 57|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_IdlStpFCO : 58|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_FCopen : 59|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Ems_ActEcoAct : 60|1@1+ (1,0) [0|1] "" CLU,IBOX,TCU + SG_ CF_Ems_EngRunNorm : 61|1@1+ (1,0) [0|1] "" ABS,ESC,IBOX,TCU + SG_ CF_Ems_IsgStat2 : 62|2@1+ (2,0) [0|3] "" CLU,IBOX,TCU + +BO_ 1419 LCA11: 8 LCA + SG_ CF_Lca_Stat : 0|4@1+ (1,0) [0|15] "" BCM,CLU + SG_ CF_Rcta_Stat : 4|4@1+ (1,0) [0|15] "" BCM,CLU + SG_ CF_Lca_IndLeft : 8|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_Rcw_Stat : 10|4@1+ (1,0) [0|15] "" BCM,CLU + SG_ CF_RCW_Warning : 14|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_Lca_IndRight : 16|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_Lca_SndWan_Stat : 18|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_FR_SndWan : 20|1@1+ (1,0) [0|1] "" BCM,CLU + SG_ CF_FL_SndWan : 21|1@1+ (1,0) [0|1] "" BCM,CLU + SG_ CF_RR_SndWan : 22|1@1+ (1,0) [0|1] "" BCM,CLU + SG_ CF_RL_SndWan : 23|1@1+ (1,0) [0|1] "" BCM,CLU + SG_ CF_Lca_IndBriLeft : 24|8@1+ (1,0) [0|255] "" BCM,CLU + SG_ CF_Lca_IndBriRight : 32|8@1+ (1,0) [0|255] "" BCM,CLU + SG_ CF_RCTA_IndBriLeft : 40|8@1+ (1,0) [0|255] "" BCM,CLU + SG_ CF_RCTA_IndBriRight : 48|8@1+ (1,0) [0|255] "" BCM,CLU + SG_ CF_RCTA_IndLeft : 56|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_RCTA_IndRight : 58|2@1+ (1,0) [0|3] "" BCM,CLU + SG_ CF_SndWarnForClu : 60|1@1+ (1,0) [0|1] "" CLU + +BO_ 906 ABS11: 8 ABS + SG_ ABS_DEF : 0|1@1+ (1,0) [0|1] "" _4WD,ACU,EMS,SPAS,TCU + SG_ EBD_DEF : 1|1@1+ (1,0) [0|1] "" _4WD,EMS,SPAS,TCU + SG_ ABS_ACT : 2|1@1+ (1,0) [0|1] "" _4WD,ACU,EPB,SPAS,TCU + SG_ ABS_W_LAMP : 3|1@1+ (1,0) [0|1] "" _4WD,CLU,CUBIS,MTS,TMU + SG_ EBD_W_LAMP : 4|1@1+ (1,0) [0|1] "" _4WD,CLU + SG_ ABS_DIAG : 5|1@1+ (1,0) [0|1] "" _4WD,CLU + SG_ ESS_STAT : 6|2@1+ (1,0) [0|3] "" _4WD,BCM,CLU,EMS + +BO_ 903 WHL_PUL11: 6 ABS + SG_ WHL_PUL_FL : 0|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_FR : 8|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RL : 16|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RR : 24|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_DIR_FL : 32|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_FR : 34|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RL : 36|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RR : 38|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_PUL_Chksum : 40|8@1+ (1,0) [0|255] "" EPB,SPAS,TPMS,EPB,LCA,LDWS_LKAS,SPAS,TPMS + +BO_ 1415 TMU11: 8 IBOX + SG_ CF_Tmu_VehSld : 0|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Tmu_VehImmo : 1|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Tmu_ReqRepCnd : 2|2@1+ (1,0) [0|3] "" EMS + SG_ CF_Tmu_AirconCtr : 4|1@1+ (1,0) [0|1] "" DATC + SG_ CF_Tmu_TempMd : 5|1@1+ (1,0) [0|1] "" DATC + SG_ CF_Tmu_TempSet : 6|16@1+ (1,0) [0|20] "" DATC + SG_ CF_Tmu_DefrostCtr : 22|1@1+ (1,0) [0|1] "" DATC,FATC + SG_ CF_Tmu_AliveCnt1 : 56|4@1+ (1,0) [0|15] "" EMS + +BO_ 902 WHL_SPD11: 8 ABS + SG_ WHL_SPD_FL : 0|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_FR : 16|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,ACU,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RL : 32|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,BCM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,BCM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RR : 48|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_AliveCounter_LSB : 14|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_AliveCounter_MSB : 30|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_LSB : 46|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_MSB : 62|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1414 EVP11: 3 EVP + SG_ CF_Evp_Stat : 0|1@1+ (1,0) [0|1] "" CLU + +BO_ 1412 AAF11: 8 AAF + SG_ CF_Aaf_ActFlapStatus : 0|2@1+ (1,0) [0|3] "" AAF_Tester + SG_ CF_Aaf_ModeStatus : 2|3@1+ (1,0) [0|7] "" AAF_Tester + SG_ CF_Aaf_WrnLamp : 5|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Aaf_ErrStatus : 6|10@1+ (1,0) [0|1023] "" AAF_Tester,EMS + SG_ CF_Aaf_OpenRqSysAct : 16|8@1+ (1,0) [0|255] "" AAF_Tester + SG_ CF_Aaf_PStatus : 24|8@1+ (1,0) [0|100] "%" AAF_Tester + SG_ CF_Aaf_OpenRqSysSol : 32|8@1+ (1,0) [0|255] "" AAF_Tester + SG_ CF_Aaf_SolFlapStatus : 40|2@1+ (1,0) [0|3] "" AAF_Tester + SG_ CF_Aaf_MilOnReq : 42|1@1+ (1,0) [0|1] "" EMS + +BO_ 900 EMS17: 8 EMS + SG_ CF_Ems_PkpCurMSV : 0|8@1+ (1,0) [0|255] "" DI_BOX + SG_ CF_Ems_HolCurMSV : 8|8@1+ (1,0) [0|255] "" DI_BOX + SG_ CF_Ems_InjVBnkAct : 16|8@1+ (1,0) [0|255] "" DI_BOX + SG_ CF_Ems_InjVActSet : 24|8@1+ (1,0) [0|255] "" DI_BOX + SG_ CF_Ems_DiagFulHDEV : 32|1@1+ (1,0) [0|1] "" DI_BOX + SG_ CF_Ems_SwiOffIC1 : 33|1@1+ (1,0) [0|1] "" DI_BOX + SG_ CF_Ems_SwiOffIC2 : 34|1@1+ (1,0) [0|1] "" DI_BOX + SG_ CF_Ems_DiagReqHDEV : 38|1@1+ (1,0) [0|1] "" DI_BOX + SG_ CR_Ems_DutyCycMSV : 40|8@1+ (0.3921568627,0) [0|100] "%" DI_BOX + SG_ CR_Ems_BatVolRly : 48|8@1+ (0.1,0) [0|25.5] "V" DI_BOX + +BO_ 387 REA11: 8 REA + SG_ CF_EndBst_PwmDuH : 0|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_PwmDuL : 1|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_PwmFqOutRng : 2|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_HbriOverCur : 3|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_HbriOverTemp : 4|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_PosSnsKOR : 6|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_PosSnsOSOR : 7|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_EepFlt : 8|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_RomFlt : 9|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_RamFlt : 10|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_CanFlt : 11|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_AgH : 12|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_AgL : 13|1@1+ (1,0) [0|1] "" EMS + SG_ CF_EndBst_ORVol : 14|1@1+ (1,0) [0|1] "" EMS + SG_ CR_EndBst_ActPos : 16|16@1+ (0.117,0) [1.989|118.053] "" EMS + SG_ CR_EndBst_DemPos : 32|16@1+ (0.117,0) [0|119.691] "" EMS + SG_ CR_EndBst_HbriPwr : 48|16@1+ (0.045,0) [0|99.99] "%" EMS + +BO_ 1411 CUBIS11: 8 CUBIS + SG_ CF_Cubis_HUDisp : 0|4@1+ (1,0) [0|15] "" CLU + +BO_ 899 FATC11: 8 DATC + SG_ CR_Fatc_TqAcnOut : 0|8@1+ (0.2,0) [0|50.8] "Nm" EMS,IBOX + SG_ CF_Fatc_AcnRqSwi : 8|1@1+ (1,0) [0|1] "" AAF,EMS,IBOX + SG_ CF_Fatc_AcnCltEnRq : 9|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Fatc_EcvFlt : 10|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Fatc_BlwrOn : 11|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_FATC_Iden : 12|2@1+ (1,0) [0|3] "" EMS,IBOX + SG_ CF_Fatc_BlwrMax : 14|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX + SG_ CF_Fatc_EngStartReq : 15|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Fatc_IsgStopReq : 16|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Fatc_CtrInf : 17|3@1+ (1,0) [0|7] "" EMS,IBOX + SG_ CF_Fatc_MsgCnt : 20|4@1+ (1,0) [0|15] "" EMS,IBOX + SG_ CR_Fatc_OutTemp : 24|8@1+ (0.5,-40) [-40|60] "deg" BCM,CLU,EMS,IBOX,SPAS,TCU,TPMS + SG_ CR_Fatc_OutTempSns : 32|8@1+ (0.5,-40) [-40|60] "deg" AAF,AHLS,CLU,EMS,IBOX,SPAS,TCU + SG_ CF_Fatc_Compload : 40|3@1+ (1,0) [0|7] "" EMS,IBOX + SG_ CF_Fatc_ActiveEco : 43|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Fatc_AutoActivation : 44|1@1+ (1,0) [0|1] "" IBOX + SG_ CF_Fatc_DefSw : 45|1@1+ (1,0) [0|1] "" BCM,IBOX + SG_ CF_Fatc_PtcRlyStat : 46|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Fatc_ChkSum : 56|8@1+ (1,0) [0|255] "" EMS,IBOX,SPAS + +BO_ 129 EMS_DCT12: 8 EMS + SG_ CR_Ems_SoakTimeExt : 0|6@1+ (5,0) [0|315] "Min" TCU + SG_ BRAKE_ACT : 6|2@1+ (1,0) [0|3] "" TCU + SG_ CF_Ems_EngOperStat : 8|8@1+ (1,0) [0|255] "" TCU + SG_ CR_Ems_IndAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "deg" TCU + SG_ CF_Ems_Alive2 : 56|4@1+ (1,0) [0|15] "" TCU + SG_ CF_Ems_ChkSum2 : 60|4@1+ (1,0) [0|15] "" TCU + +BO_ 897 MDPS11: 8 MDPS + SG_ CF_Mdps_WLmp : 0|2@1+ (1,0) [0|3] "" CLU,CUBIS,EMS,IBOX,SPAS + SG_ CF_Mdps_Flex : 2|3@1+ (1,0) [0|3] "" CLU,LDWS_LKAS + SG_ CF_Mdps_FlexDisp : 5|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Mdps_Stat : 7|4@1+ (1,0) [0|15] "" SPAS + SG_ CR_Mdps_DrvTq : 11|12@1+ (0.01,-20.48) [-20.48|20.46] "" SPAS + SG_ CF_Mdps_ALTRequest : 23|1@1+ (1,0) [0|1] "" EMS + SG_ CR_Mdps_StrAng : 24|16@1- (0.1,0) [-3276.8|3276.7] "Deg" SPAS + SG_ CF_Mdps_AliveCnt : 40|8@1+ (1,0) [0|255] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_Chksum : 48|8@1+ (1,0) [0|255] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_SPAS_FUNC : 57|1@1+ (1,0) [0|1] "flag" SPAS + SG_ CF_Mdps_LKAS_FUNC : 58|1@1+ (1,0) [0|1] "flag" LDWS_LKAS + SG_ CF_Mdps_CurrMode : 59|2@1+ (1,0) [0|3] "" LDWS_LKAS + SG_ CF_Mdps_Type : 61|2@1+ (1,0) [0|2] "" LDWS_LKAS,SPAS + +BO_ 896 DI_BOX13: 8 DI_BOX + SG_ CF_DiBox_HPreInjVConfStat : 0|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_HPreInjVStat1 : 8|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_HPreInjVStat2 : 16|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_HPreInjVPkp : 24|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_HPreInjVBpt : 32|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_ErrRegFrtMSV : 40|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_ErrRegSedMSV : 48|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_SPIErrSedMSV : 56|1@1+ (1,0) [0|1] "" EMS + SG_ CF_DiBox_SPIErrFrtMSV : 57|1@1+ (1,0) [0|1] "" EMS + SG_ CF_DiBox_IDErrSedMSV : 58|1@1+ (1,0) [0|1] "" EMS + SG_ CF_DiBox_IDErrFrtMSV : 59|1@1+ (1,0) [0|1] "" EMS + SG_ CF_DiBox_IniStatMSV : 60|1@1+ (1,0) [0|1] "" EMS + +BO_ 128 EMS_DCT11: 8 EMS + SG_ PV_AV_CAN : 0|8@1+ (0.3906,0) [0|99.603] "%" TCU + SG_ TQ_STND : 8|6@1+ (10,0) [0|630] "Nm" TCU + SG_ F_N_ENG : 14|1@1+ (1,0) [0|1] "" TCU + SG_ F_SUB_TQI : 15|1@1+ (1,0) [0|1] "" TCU + SG_ N : 16|16@1+ (0.25,0) [0|16383.75] "rpm" TCU + SG_ TQI_ACOR : 32|8@1+ (0.390625,0) [0|99.6094] "%" IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" TCU + SG_ TQI : 48|8@1+ (0.390625,0) [0|99.609375] "%" TCU + SG_ CF_Ems_Alive : 56|4@1+ (1,0) [0|15] "" TCU + SG_ CF_Ems_ChkSum : 60|4@1+ (1,0) [0|15] "" TCU + +BO_ 1407 HU_MON_PE_01: 8 CLU + SG_ HU_Type : 0|8@1+ (1,0) [0|255] "" AVM,PGS + +BO_ 127 CGW5: 8 BCM + SG_ C_StopLampLhOpenSts : 0|1@1+ (1,0) [0|1] "" CLU + SG_ C_StopLampRhOpenSts : 1|1@1+ (1,0) [0|1] "" CLU + SG_ C_HMSLOpenSts : 2|1@1+ (1,0) [0|1] "" CLU + SG_ C_HLampLowLhOpenSts : 3|1@1+ (1,0) [0|1] "" CLU + SG_ C_HLampLowRhOpenSts : 4|1@1+ (1,0) [0|1] "" CLU + SG_ C_HLampHighLhOpenSts : 5|1@1+ (1,0) [0|1] "" CLU + SG_ C_HLampHighRhOpenSts : 6|1@1+ (1,0) [0|1] "" CLU + SG_ C_DRLLampLhOpenSts : 7|1@1+ (1,0) [0|1] "" CLU + SG_ C_DRLLampRhOpenSts : 8|1@1+ (1,0) [0|1] "" CLU + SG_ C_RearFOGLhOpenSts : 9|1@1+ (1,0) [0|1] "" CLU + SG_ C_RearFOGRhOpenSts : 10|1@1+ (1,0) [0|1] "" CLU + SG_ C_FrontFOGLhOpenSts : 11|1@1+ (1,0) [0|1] "" CLU + SG_ C_FrontFOGRhOpenSts : 12|1@1+ (1,0) [0|1] "" CLU + SG_ C_RearEXTTailLhOpenSts : 13|1@1+ (1,0) [0|1] "" CLU + SG_ C_RearEXTTailRhOpenSts : 14|1@1+ (1,0) [0|1] "" CLU + SG_ C_FrontEXTTailLhOpenSts : 15|1@1+ (1,0) [0|1] "" CLU + SG_ C_FrontEXTTailRhOpenSts : 16|1@1+ (1,0) [0|1] "" CLU + SG_ C_RearTSIGLhOpenSts : 17|1@1+ (1,0) [0|1] "" CLU + SG_ C_RearTSIGRhOpenSts : 18|1@1+ (1,0) [0|1] "" CLU + SG_ C_FrontTSIGLhOpenSts : 19|1@1+ (1,0) [0|1] "" CLU + SG_ C_FrontTSIGRhOpenSts : 20|1@1+ (1,0) [0|1] "" CLU + SG_ C_SBendingLhOpenSts : 21|1@1+ (1,0) [0|1] "" CLU + SG_ C_SBendingRhOpenSts : 22|1@1+ (1,0) [0|1] "" CLU + SG_ C_LicensePlateLhOpenSts : 23|1@1+ (1,0) [0|1] "" CLU + SG_ C_LicensePlateRhOpenSts : 24|1@1+ (1,0) [0|1] "" CLU + +BO_ 1151 ESP11: 6 ESC + SG_ AVH_STAT : 0|2@1+ (1,0) [0|3] "" EMS,EPB,TCU + SG_ LDM_STAT : 2|1@1+ (1,0) [0|1] "" EPB,TCU + SG_ REQ_EPB_ACT : 3|2@1+ (1,0) [0|3] "" EPB,TCU + SG_ REQ_EPB_STAT : 5|1@1+ (1,0) [0|1] "" EPB + SG_ ECD_ACT : 6|1@1+ (1,0) [0|1] "" EPB + SG_ _4WD_LIM_REQ : 7|1@1+ (1,0) [0|1] "" _4WD,EMS + SG_ ROL_CNT_ESP : 8|8@1+ (1,0) [0|255] "" EPB,TCU + SG_ _4WD_TQC_LIM : 16|16@1+ (1,0) [0|65535] "Nm" _4WD,EMS + SG_ _4WD_CLU_LIM : 32|8@1+ (0.390625,0) [0|99.609375] "%" _4WD,EMS + SG_ _4WD_OPEN : 40|2@1+ (1,0) [0|3] "" _4WD,EMS + SG_ _4WD_LIM_MODE : 42|1@1+ (1,0) [0|1] "" _4WD + +BO_ 1397 HU_AVM_E_00: 8 CLU + SG_ HU_AVM_Cal_Cmd : 0|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_Cal_Method : 4|2@1+ (1,0) [0|3] "" AVM,PGS + SG_ HU_AVM_Save_Controlpoint : 6|2@1+ (1,0) [0|3] "" AVM,PGS + SG_ HU_AVM_PT_X : 8|12@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_RearViewPointOpt : 20|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_PT_Y : 24|12@1+ (1,0) [0|4095] "" AVM,PGS + SG_ HU_AVM_FrontViewPointOpt : 36|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_SelectedMenu : 40|5@1+ (1,0) [0|31] "" AVM,PGS + SG_ HU_AVM_CameraOff : 45|2@1+ (1,0) [0|3] "" AVM,PGS + SG_ HU_AVM_Option : 48|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_CrossLineMove_Cmd : 52|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_RearView_Option : 56|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_FrontView_Option : 60|4@1+ (1,0) [0|15] "" AVM,PGS + +BO_ 1395 HU_AVM_E_01: 8 CLU + SG_ HU_PGSSelectedMenu : 0|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_PGSOption : 8|5@1+ (1,0) [0|31] "" AVM,PGS + SG_ HU_AVM_ParkingAssistMenu : 56|4@1+ (1,0) [0|15] "" AVM,PGS + SG_ HU_AVM_ParkingAssistSB : 60|4@1+ (1,0) [0|15] "" AVM,PGS + +BO_ 1393 OPI11: 5 OPI + SG_ CR_Opi_Spd_Rpm : 0|8@1+ (20,0) [0|3500] "rpm" TCU + SG_ CF_Opi_Over_Temp : 8|1@1+ (1,0) [0|1] "" TCU + SG_ CF_Opi_Over_Cur : 9|1@1+ (1,0) [0|1] "" EMS,TCU + SG_ CF_Opi_Over_Vol : 10|1@1+ (1,0) [0|1] "" TCU + SG_ CF_Opi_Hall_Fail : 11|1@1+ (1,0) [0|1] "" EMS,TCU + SG_ CF_Opi_Flt : 12|1@1+ (1,0) [0|1] "" EMS,TCU + SG_ CF_Opi_Motor_Dir : 15|1@1+ (1,0) [0|1] "" TCU + SG_ CF_Opi_Romver : 16|8@1+ (1,0) [0|255] "" TCU + SG_ CF_Opi_PWM_Rate : 24|12@1+ (1,0) [0|100] "%" TCU + +BO_ 625 LPI11: 8 LPI + SG_ FUP_LPG_MMV : 0|8@1+ (128,0) [0|32640] "hPa" EMS + SG_ LV_FUEL_TYPE_BOX : 8|1@1+ (1,0) [0|1] "" EMS + SG_ LV_BFS_IN_PROGRESS : 9|1@1+ (1,0) [0|1] "" EMS + SG_ LV_GAS_OK : 10|1@1+ (1,0) [0|1] "" EMS + SG_ LV_FUP_ENA_THD : 11|1@1+ (1,0) [0|1] "" BCM,CLU,EMS,SMK + SG_ LPI_OBD : 12|4@1+ (1,0) [0|15] "" EMS + SG_ ERR_GAS : 16|8@1+ (1,0) [0|255] "" EMS + SG_ FAC_TI_GAS_COR : 24|16@1+ (0.0000305,0) [0|1.9988175] "" EMS + SG_ FTL_AFU : 40|8@1+ (0.392,0) [0|99.96] "%" EMS + SG_ BFS_CYL : 48|8@1+ (1,0) [0|6] "Cyl Nr." EMS + SG_ LV_PRE_CDN_LEAK : 56|1@1+ (1,0) [0|1] "" EMS + SG_ LV_CONF_INJECTION_DELAY : 57|1@1+ (1,0) [0|1] "" EMS + SG_ LV_LPG_SW_DRIVER_REQ : 58|1@1+ (1,0) [0|1] "" EMS + +BO_ 356 VSM11: 4 ESC + SG_ CR_Esc_StrTqReq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" MDPS + SG_ CF_Esc_Act : 12|1@1+ (1,0) [0|1] "" LDWS_LKAS,MDPS + SG_ CF_Esc_CtrMode : 13|3@1+ (1,0) [0|7] "" MDPS + SG_ CF_Esc_Def : 16|1@1+ (1,0) [0|1] "" MDPS + SG_ CF_Esc_AliveCnt : 17|4@1+ (1,0) [0|15] "" LDWS_LKAS,MDPS + SG_ CF_Esc_Chksum : 24|8@1+ (1,0) [0|255] "" LDWS_LKAS,MDPS + +BO_ 1379 PGS_HU_PE_01: 8 PGS + SG_ PGS_State : 0|4@1+ (1,0) [0|15] "" CLU + SG_ PGS_ParkGuideState : 8|5@1+ (1,0) [0|31] "" CLU + SG_ PGS_Option : 16|5@1+ (1,0) [0|31] "" CLU + SG_ PGS_Version : 32|16@1+ (1,0) [0|65535] "" CLU + +BO_ 354 TCU_DCT13: 3 TCU + SG_ Clutch_Driving_Tq : 0|10@1+ (1,-512) [0|0] "Nm" ESC + SG_ Cluster_Engine_RPM : 10|13@1+ (0.9766,0) [0|0] "" CLU + SG_ Cluster_Engine_RPM_Flag : 23|1@1+ (1,0) [0|0] "" CLU + +BO_ 1378 HUD11: 4 HUD + SG_ CF_Hud_HeightStaus : 0|5@1+ (1,0) [0|31] "" CLU + SG_ CF_Hud_PBackStatus : 6|2@1+ (1,0) [0|0] "" BCM,CLU + SG_ CF_Hud_Brightness : 8|5@1+ (1,0) [0|31] "" CLU + +BO_ 608 EMS16: 8 EMS + SG_ GLOW_STAT : 24|1@1+ (1,0) [0|1] "" BCM,CLU,IBOX,SMK + SG_ CRUISE_LAMP_M : 25|1@1+ (1,0) [0|1] "" CLU,IBOX,TCU + SG_ CRUISE_LAMP_S : 26|1@1+ (1,0) [0|1] "" CLU,IBOX,TCU + SG_ PRE_FUEL_CUT_IN : 27|1@1+ (1,0) [0|1] "" IBOX,TCU + SG_ SOAK_TIME_ERROR : 31|1@1+ (1,0) [0|1] "" DATC,EPB,IBOX,TCU + SG_ TQI_MAX : 40|8@1+ (0.390625,0) [0|99.609375] "%" ESC,IBOX,TCU + SG_ SPK_TIME_CUR : 48|8@1+ (0.375,-35.625) [-35.625|60] "" IBOX,TCU + SG_ Checksum : 56|4@1+ (1,0) [0|15] "" ECS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ AliveCounter : 60|2@1+ (1,0) [0|3] "" IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Ems_AclAct : 62|2@1+ (1,0) [0|3] "" IBOX,SCC + SG_ TQI : 8|8@1+ (1.7,0) [0|440] "%" ESC,IBOX,TCU + SG_ TQI_MIN : 0|8@1+ (1.7,0) [0|99.609375] "nm" ESC,IBOX,TCU + SG_ TQI_TARGET : 16|8@1+ (1.7,0) [0|440] "nm" EPB,ESC,IBOX,TCU + SG_ ENG_STAT : 28|3@1+ (1,0) [0|7] "" ABS,AHLS,AVM,BCM,CLU,EPB,ESC,EVP,FPCM,IBOX,LCA,LDWS_LKAS,MDPS,SCC,SMK,TCU + SG_ SOAK_TIME : 32|8@1+ (1,0) [0|255] "Min" _4WD,DATC,EPB,IBOX,TCU + +BO_ 1371 AVM_HU_PE_00: 8 AVM + SG_ AVM_View : 0|5@1+ (1,0) [0|31] "" CLU + SG_ AVM_ParkingAssist_BtnSts : 5|3@1+ (1,0) [0|7] "" CLU + SG_ AVM_Display_Message : 8|8@1+ (1,0) [0|255] "" CLU + SG_ AVM_Popup_Msg : 16|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_Ready : 20|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_ParkingAssist_Step : 24|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_FrontBtn_Type : 28|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_Option : 32|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_HU_FrontViewPointOpt : 36|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_HU_RearView_Option : 40|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_HU_FrontView_Option : 44|4@1+ (1,0) [0|15] "" CLU + SG_ AVM_Version : 48|16@1+ (1,0) [0|65535] "" CLU + +BO_ 1370 HU_AVM_PE_00: 8 CLU + SG_ HU_AVM_Status : 0|2@1+ (1,0) [0|3] "" AVM,PGS + +BO_ 1369 CGW4: 8 BCM + SG_ CF_Gway_MemoryP1Cmd : 0|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_MemoryP2Cmd : 1|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_PBackP1Cmd : 2|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_PBackP2Cmd : 3|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_StrgWhlHeatedState : 4|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_PBackStopCmd : 5|1@1+ (1,0) [0|1] "" CLU,HUD + SG_ CF_Gway_StaticBendLhAct : 6|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_StaticBendRhAct : 7|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_DrvWdwStat : 8|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_RLWdwState : 9|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_RRWdwState : 10|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_AstWdwStat : 11|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_MemoryEnable : 12|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_PBACKStopCmd : 13|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_PBACKStop : 14|1@1+ (1,0) [0|1] "" CLU,HUD + SG_ CF_Gway_IMSBuzzer : 15|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_DrvSeatBeltInd : 36|2@1+ (1,0) [0|3] "" CLU,Dummy + SG_ CF_Gway_AstSeatBeltInd : 38|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_RCSeatBeltInd : 40|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_RLSeatBeltInd : 42|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_RRSeatBeltInd : 44|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_RrWiperHighSw : 46|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_RrWiperLowSw : 47|1@1+ (1,0) [0|1] "" CLU + +BO_ 1367 EngFrzFrm12: 8 EMS + SG_ PID_06h : 0|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU + SG_ PID_07h : 8|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU + SG_ PID_08h : 16|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU + SG_ PID_09h : 24|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU + SG_ PID_0Bh : 32|8@1+ (1,0) [0|255] "kPa" AAF,IBOX,TCU + SG_ PID_23h : 40|16@1+ (10,0) [0|655350] "kPa" AAF,IBOX,TCU + +BO_ 1366 EngFrzFrm11: 8 EMS + SG_ PID_04h : 0|8@1+ (0.3921568627,0) [0|100] "%" AAF,TCU + SG_ PID_05h : 8|8@1+ (1,-40) [-40|215] "deg" AAF,TCU + SG_ PID_0Ch : 16|16@1+ (0.25,0) [0|16383.75] "rpm" AAF,TCU + SG_ PID_0Dh : 32|8@1+ (1,0) [0|255] "km/h" AAF,TCU + SG_ PID_11h : 40|8@1+ (0.3921568627,0) [0|100] "%" AAF,TCU + SG_ PID_03h : 48|16@1+ (1,0) [0|65535] "" AAF,TCU + +BO_ 1365 FPCM11: 8 FPCM + SG_ CR_Fpcm_LPActPre : 0|8@1+ (3.137254902,0) [0|800] "kPa" EMS + SG_ CF_Fpcm_LPPumpOverCur : 8|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Fpcm_PreSnrHi : 9|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Fpcm_PreSnrDisc : 10|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Fpcm_PreSnrShort : 11|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Fpcm_LPPumpDiscShort : 12|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Fpcm_LP_System_Error : 13|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Fpcm_PreSnrSigErr : 14|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Fpcm_LPCtrCirFlt : 15|1@1+ (1,0) [0|1] "" EMS + +BO_ 852 LVR11: 7 LVR + SG_ CF_Lvr_GearInf : 0|4@1+ (1,0) [0|15] "" CLU,TCU + SG_ CF_Lvr_PRelStat : 4|1@1+ (1,0) [0|1] "" BCM,CLU,SMK,TCU + SG_ CF_Lvr_BkeAct : 5|1@1+ (1,0) [0|1] "" TCU + SG_ CF_Lvr_NFnStat : 6|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Lvr_PosInf : 8|4@1+ (1,0) [0|15] "" TCU + SG_ CF_Lvr_PosCpl : 12|4@1+ (1,0) [0|15] "" TCU + SG_ CF_Lvr_UlkButStat : 18|2@1+ (1,0) [0|3] "" TCU + SG_ CF_Lvr_PNStat : 20|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Lvr_ShtLkStat : 24|4@1+ (1,0) [0|15] "" TCU + SG_ CF_Lvr_ShfErrInf : 28|20@1+ (1,0) [0|8191] "" CLU,TCU + SG_ CF_Lvr_AC : 48|4@1+ (1,0) [0|15] "" TCU + SG_ CF_Lvr_CS : 52|4@1+ (1,0) [0|15] "" TCU + +BO_ 1363 CGW2: 8 BCM + SG_ CF_Gway_GwayDiagState : 0|1@1+ (1,0) [0|3] "" CLU,Dummy + SG_ CF_Gway_DDMDiagState : 1|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_SCMDiagState : 2|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_PSMDiagState : 3|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_SJBDiagState : 4|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_IPMDiagState : 5|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_LDMFail : 6|2@1+ (1,0) [0|3] "" CLU,LDWS_LKAS,LDWS_LKAS + SG_ CF_Gway_CLUSwGuiCtrl : 10|3@1+ (1,0) [0|63] "" CLU,Dummy + SG_ CF_Gway_CLUSwGroup : 13|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_CLUSwMode : 14|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_CLUSwEnter : 15|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_AutoLightValue : 16|1@1+ (1,0) [0|1] "" LCA,LCA + SG_ CF_Gway_BrakeFluidSw : 17|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_DrvSeatBeltInd : 18|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_AvTail : 20|1@1+ (1,0) [0|3] "" CLU,SNV,SNV + SG_ CF_Gway_RearFogAct : 21|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_ExtTailAct : 22|1@1+ (1,0) [0|1] "" AVM,CLU,LCA,PGS,SPAS,AVM,LCA,PGS,SPAS + SG_ CF_Gway_RRDrSw : 23|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_RLDrSw : 24|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_IntTailAct : 25|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_CountryCfg : 26|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,Dummy + SG_ CF_Gway_WiperParkPosition : 32|1@1+ (1,0) [0|1] "" AFLS,EMS,LDWS_LKAS,AFLS,EMS,LDWS_LKAS + SG_ CF_Gway_HLLowLHFail : 33|1@1+ (1,0) [0|1] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_HLLowRHFail : 34|1@1+ (1,0) [0|1] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_ESCLFailWarn : 35|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_ESCLNotLockedWarn : 36|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_ESCLNotUnlockWarn : 37|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_IDoutWarn : 38|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_ImmoLp : 40|1@1+ (1,0) [0|3] "" CLU,Dummy + SG_ CF_Gway_BCMRKEID : 41|3@1+ (1,0) [0|7] "" CLU,Dummy + SG_ CF_Gway_VehicleNotPWarn : 44|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_DeactivationWarn : 45|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_KeyBATDischargeWarn : 46|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_SSBWarn : 47|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_SMKFobID : 48|3@1+ (1,0) [0|7] "" CLU,Dummy + SG_ CF_Gway_SMKRKECmd : 51|3@1+ (1,0) [0|7] "" CLU,Dummy + SG_ CF_Gway_AutoLightOption : 54|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_SJBDeliveryMode : 55|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_KeyoutLp : 56|1@1+ (1,0) [0|1] "" CLU,Dummy + SG_ CF_Gway_SMKDispWarn : 57|4@1+ (1,0) [0|15] "" CLU,Dummy + SG_ CF_Gway_WngBuz : 61|3@1+ (1,0) [0|7] "" CLU,Dummy + +BO_ 339 TCS11: 8 ESC + SG_ TCS_REQ : 0|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,TCU + SG_ MSR_C_REQ : 1|1@1+ (1,0) [0|1] "" EMS,EPB,SCC,TCU + SG_ TCS_PAS : 2|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,SCC,SPAS,TCU + SG_ TCS_GSC : 3|1@1+ (1,0) [0|1] "" _4WD,EMS,TCU + SG_ CF_Esc_LimoInfo : 4|2@1+ (1,0) [0|3] "" _4WD,SCC + SG_ ABS_DIAG : 6|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB + SG_ ABS_DEF : 7|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_DEF : 8|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_CTL : 9|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ ABS_ACT : 10|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ EBD_DEF : 11|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,SPAS,TCU + SG_ ESP_PAS : 12|1@1+ (1,0) [0|1] "" _4WD,ACU,CLU,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_DEF : 13|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_CTL : 14|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ TCS_MFRN : 15|1@1+ (1,0) [0|1] "" EMS,EPB,TCU + SG_ DBC_CTL : 16|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB + SG_ DBC_PAS : 17|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB + SG_ DBC_DEF : 18|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB + SG_ HAC_CTL : 19|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_PAS : 20|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_DEF : 21|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB,TCU + SG_ ESS_STAT : 22|2@1+ (1,0) [0|3] "" _4WD,BCM,CLU,EMS,EPB + SG_ TQI_TCS : 24|8@1+ (0.390625,0) [0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_MSR : 32|8@1+ (0.390625,0) [0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_SLW_TCS : 40|8@1+ (0.390625,0) [0|99.609375] "%" EMS,EPB,TCU + SG_ CF_Esc_BrkCtl : 48|1@1+ (1,0) [0|1] "" EMS + SG_ BLA_CTL : 49|2@1+ (1,0) [0|3] "" BCM,CGW,CLU + SG_ AliveCounter_TCS1 : 52|4@1+ (1,0) [0|14] "" EMS,EPB,LDWS_LKAS + SG_ CheckSum_TCS1 : 56|8@1+ (1,0) [0|255] "" EMS,EPB,LDWS_LKAS + +BO_ 1362 SNV11: 4 SNV + SG_ CF_SNV_DisplayControl : 0|2@1+ (1,0) [0|3] "" CLU,HUD + SG_ CF_Snv_BeepWarning : 2|2@1+ (1,0) [0|3] "" CLU,HUD + SG_ CF_Snv_WarningMessage : 4|3@1+ (1,0) [0|7] "" CLU,HUD + SG_ CF_Snv_DetectionEnable : 7|1@1+ (1,0) [0|1] "" BCM,CLU,HUD + SG_ CF_Snv_PedestrianDetect : 8|2@1+ (1,0) [0|3] "" BCM,CLU,HUD + SG_ CF_Snv_IRLampControl : 10|2@1+ (1,0) [0|3] "" BCM,CLU,HUD + +BO_ 593 MDPS12: 8 MDPS + SG_ CR_Mdps_StrColTq : 0|11@1+ (0.0078125,-8) [-8|7.9921875] "Nm" LDWS_LKAS + SG_ CF_Mdps_Def : 11|1@1+ (1,0) [0|1] "" ESC + SG_ CF_Mdps_ToiUnavail : 12|1@1+ (1,0) [0|1] "" LDWS_LKAS + SG_ CF_Mdps_ToiActive : 13|1@1+ (1,0) [0|1] "" LDWS_LKAS + SG_ CF_Mdps_ToiFlt : 14|1@1+ (1,0) [0|1] "" LDWS_LKAS + SG_ CF_Mdps_FailStat : 15|1@1+ (1,0) [0|1] "" LDWS_LKAS + SG_ CF_Mdps_MsgCount2 : 16|8@1+ (1,0) [0|255] "" ESC,LDWS_LKAS + SG_ CF_Mdps_Chksum2 : 24|8@1+ (1,0) [0|255] "" ESC,LDWS_LKAS + SG_ CF_Mdps_SErr : 37|1@1+ (1,0) [0|1] "" ESC + SG_ CR_Mdps_StrTq : 40|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" ESC + SG_ CR_Mdps_OutTq : 52|12@1+ (0.1,-204.8) [-204.8|204.7] "" ESC,LDWS_LKAS + +BO_ 1360 IAP11: 3 IAP + SG_ CF_Iap_EcoPmodSwi : 0|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Iap_EcoPmodAct : 1|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Iap_ReqWarn : 2|2@1+ (1,0) [0|3] "" CLU + +BO_ 1356 TCU_DCT14: 8 TCU + SG_ Vehicle_Stop_Time : 0|5@1+ (1,0) [0|0] "" CLU + SG_ HILL_HOLD_WARNING : 5|1@1+ (1,0) [0|0] "" CLU + +BO_ 1353 BAT11: 8 EMS + SG_ BAT_SNSR_I : 0|16@1+ (0.01,-327) [-327|328] "A" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOC : 16|8@1+ (1,0) [0|100] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_V : 24|14@1+ (0.001,6) [6|18] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Temp : 38|9@1- (0.5,-40) [-40|125] "deg" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_State : 47|1@1+ (1,0) [0|1] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOH : 48|7@1+ (1,0) [0|100] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Invalid : 55|1@1+ (1,0) [0|1] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOF : 56|7@1+ (0.1,0) [0|12] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Error : 63|1@1+ (1,0) [0|1] "" CGW,CUBIS,IBOX,TMU + +BO_ 1351 EMS15: 8 EMS + SG_ ECGPOvrd : 0|1@1+ (1,0) [0|1] "" ESC,IBOX,SCC + SG_ QECACC : 1|1@1+ (1,0) [0|1] "" ESC,IBOX + SG_ ECFail : 2|1@1+ (1,0) [0|1] "" ESC,IBOX + SG_ SwitchOffCondExt : 3|1@1+ (1,0) [0|1] "" ESC,IBOX + SG_ BLECFail : 4|1@1+ (1,0) [0|1] "" ESC,IBOX + SG_ CF_Ems_IsaAct : 5|1@1+ (1,0) [0|1] "" CLU + SG_ FA_PV_CAN : 8|8@1+ (0.3906,0) [0|99.2] "%" IBOX,LDWS_LKAS,TCU + SG_ IntAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "deg" _4WD,ECS,EPB,IBOX,TCU + SG_ STATE_DC_OBD : 24|7@1+ (1,0) [0|127] "" IBOX,TCU + SG_ INH_DC_OBD : 31|1@1+ (1,0) [0|1] "" IBOX,TCU + SG_ CTR_IG_CYC_OBD : 32|16@1+ (1,0) [0|65535] "" ACU,IBOX,TCU + SG_ CTR_CDN_OBD : 48|16@1+ (1,0) [0|65535] "" IBOX,TCU + +BO_ 1350 DI_BOX12: 8 DI_BOX + SG_ CF_DiBox_FrtInjVDiagReg0 : 0|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg1 : 8|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg2 : 16|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_SedInjVDiagReg0 : 24|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_SedInjVDiagReg1 : 32|8@1+ (1,0) [0|255] "" EMS + SG_ CF_DiBox_SedInjVDiagReg2 : 40|8@1+ (1,0) [0|255] "" EMS + SG_ CR_DiBox_BatVol : 48|8@1+ (0.1,0) [0|25.5] "V" EMS + SG_ CF_DiBox_SedInjVChg : 56|1@1+ (1,0) [0|1] "" EMS + SG_ CF_DiBox_FrtInjVChg : 57|1@1+ (1,0) [0|1] "" EMS + SG_ CF_DiBox_SedInjVErrSPI : 58|1@1+ (1,0) [0|1] "" EMS + SG_ CF_DiBox_FrtInjVErrSPI : 59|1@1+ (1,0) [0|1] "" EMS + +BO_ 1349 EMS14: 8 EMS + SG_ IMMO_LAMP_STAT : 0|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ L_MIL : 1|1@1+ (1,0) [0|1] "" CLU,CUBIS,IBOX + SG_ IM_STAT : 2|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ AMP_CAN : 3|5@1+ (10.731613,458.98) [458.98|791.660003] "mmHg" CLU,IBOX,TCU,TPMS + SG_ BAT_Alt_FR_Duty : 8|8@1+ (0.4,0) [0|100] "%" CGW,CUBIS,IBOX,TMU + SG_ VB : 24|8@1+ (0.1015625,0) [0|25.8984375] "V" CLU,CUBIS,DATC,EPB,FPCM,IBOX + SG_ EMS_VS : 32|12@1+ (0.0625,0) [0|255.875] "km/h" CLU + SG_ TEMP_FUEL : 56|8@1+ (0.75,-48) [-48|143.25] "deg" FPCM + +BO_ 68 DATC11: 8 DATC + SG_ CF_Datc_Type : 0|8@1+ (1,0) [0|255] "" CLU + SG_ CF_Datc_VerMaj : 8|8@1+ (1,0) [0|255] "" CLU + SG_ CF_Datc_VerMin : 16|8@1+ (1,0) [0|255] "" CLU + SG_ CR_Datc_OutTempC : 24|8@1+ (0.5,-41) [-41|86.5] "deg" CLU,FPCM + SG_ CR_Datc_OutTempF : 32|8@1+ (1,-42) [-42|213] "deg" CLU + SG_ CF_Datc_IncarTemp : 40|8@1+ (0.5,-40) [-40|60] "deg" BCM,CLU + +BO_ 67 DATC13: 8 DATC + SG_ CF_Datc_TempDispUnit : 0|2@1+ (1,0) [0|3] "" CLU,IBOX + SG_ CF_Datc_ModDisp : 2|4@1+ (1,0) [0|15] "" CLU + SG_ CF_Datc_IonClean : 6|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_ChgReqDisp : 8|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_IntakeDisp : 10|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_AutoDisp : 12|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_FrDefLed : 14|2@1+ (1,0) [0|3] "" CLU,IBOX + SG_ CF_Datc_AutoDefogBlink : 16|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_ClmScanDisp : 18|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_AqsDisp : 20|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_AcDisp : 22|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_OpSts : 25|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Mtc_MaxAcDisp : 28|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_DualDisp : 30|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_PwrInf : 32|4@1+ (1,0) [0|15] "" CLU + SG_ CF_Datc_RearManual : 38|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_RearAutoDisp : 40|2@1+ (1,0) [0|1] "" CLU + SG_ CF_Datc_RearOffDisp : 42|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_RearClimateScnDisp : 44|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_RearChgReqDisp : 46|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_RearModDisp : 48|4@1+ (1,0) [0|15] "" CLU + SG_ CF_Datc_RearBlwDisp : 52|4@1+ (1,0) [0|15] "" CLU + SG_ CF_Datc_PSModDisp : 56|4@1+ (1,0) [0|15] "" CLU + SG_ CF_Datc_FrontBlwDisp : 60|4@1+ (1,0) [0|15] "" CLU,IBOX + +BO_ 66 DATC12: 8 DATC + SG_ CR_Datc_DrTempDispC : 0|8@1+ (0.5,14) [15|32] "deg" CLU,IBOX + SG_ CR_Datc_DrTempDispF : 8|8@1+ (1,56) [58|90] "��" CLU,IBOX + SG_ CR_Datc_PsTempDispC : 16|8@1+ (0.5,14) [15|32] "deg" CLU,IBOX + SG_ CR_Datc_PsTempDispF : 24|8@1+ (1,56) [58|90] "��" CLU,IBOX + SG_ CR_Datc_RearDrTempDispC : 40|8@1+ (0.5,14) [15|32] "deg" CLU + SG_ CR_Datc_RearDrTempDispF : 48|8@1+ (1,58) [58|90] "��" CLU + SG_ CF_Datc_CO2_Warning : 56|8@1+ (1,0) [0|3] "" CLU + +BO_ 1345 CGW1: 8 BCM + SG_ CF_Gway_IGNSw : 0|3@1+ (1,0) [0|7] "" AVM,CLU,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC + SG_ CF_Gway_RKECmd : 3|3@1+ (1,0) [0|7] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyLockSw : 6|1@1+ (1,0) [0|1] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyUnlockSw : 7|1@1+ (1,0) [0|1] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvDrSw : 8|2@1+ (1,0) [0|3] "" CLU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU + SG_ CF_Gway_DrvSeatBeltSw : 10|2@1+ (1,0) [0|3] "" EMS,EPB,ESC,IBOX,PSB,TCU,EMS,EPB,ESC,IBOX,PSB,TCU + SG_ CF_Gway_TrunkTgSw : 12|2@1+ (1,0) [0|3] "" CLU,ECS,EMS,EPB,ESC,IBOX,ECS,EMS,EPB,ESC,IBOX + SG_ CF_Gway_AstSeatBeltSw : 14|2@1+ (1,0) [0|3] "" IBOX,PSB,IBOX,PSB + SG_ CF_Gway_SMKOption : 16|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_HoodSw : 17|2@1+ (1,0) [0|3] "" CLU,EMS,EPB,ESC,IBOX,EMS,EPB,ESC,IBOX + SG_ CF_Gway_TurnSigLh : 19|2@1+ (1,0) [0|3] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + SG_ CF_Gway_WiperIntT : 21|3@1+ (1,0) [0|7] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperIntSw : 24|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperLowSw : 25|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperHighSw : 26|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperAutoSw : 27|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_RainSnsState : 28|3@1+ (1,0) [0|7] "" AFLS,EMS,IBOX,LDWS_LKAS,AFLS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_HeadLampLow : 31|1@1+ (1,0) [0|1] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,SNV,AFLS,EMS,IBOX,LDWS_LKAS,SNV + SG_ CF_Gway_HeadLampHigh : 32|1@1+ (1,0) [0|1] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,AFLS,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_HazardSw : 33|2@1+ (1,0) [0|3] "" ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS,ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS + SG_ CF_Gway_AstDrSw : 35|1@1+ (1,0) [0|1] "" CLU,IBOX,IBOX + SG_ CF_Gway_DefoggerRly : 36|1@1+ (1,0) [0|1] "" EMS,IBOX,EMS,IBOX + SG_ CF_Gway_ALightStat : 37|1@1+ (1,0) [0|1] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_LightSwState : 38|2@1+ (1,0) [0|3] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_Frt_Fog_Act : 40|1@1+ (1,0) [0|1] "" AFLS,CLU,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigRHSw : 41|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigLHSw : 42|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_DriveTypeOption : 43|1@1+ (1,0) [0|1] "" CLU,IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_StarterRlyState : 44|1@1+ (1,0) [0|1] "" EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_PassiveAccessLock : 45|2@1+ (1,0) [0|7] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_WiperMistSw : 47|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_PassiveAccessUnlock : 48|2@1+ (1,0) [0|7] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_RrSunRoofOpenState : 50|1@1+ (1,0) [0|1] "" CLU,DATC,IBOX + SG_ CF_Gway_PassingSW : 51|1@1+ (1,0) [0|1] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_HBAControlMode : 52|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_HLpHighSw : 53|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_InhibitRMT : 54|2@1+ (1,0) [0|3] "" EMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,MDPS,PGS,SCC,SPAS,TPMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,PGS,SCC,SPAS,TPMS + SG_ CF_Gway_RainSnsOption : 56|1@1+ (1,0) [0|1] "" CLU + SG_ C_SunRoofOpenState : 57|1@1+ (1,0) [0|1] "" CLU,DATC,IBOX,DATC,IBOX + SG_ CF_Gway_Ign1 : 58|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_Ign2 : 59|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Gway_ParkBrakeSw : 60|2@1+ (1,0) [0|3] "" CLU,ESC,IBOX,SCC,ESC,IBOX,SCC + SG_ CF_Gway_TurnSigRh : 62|2@1+ (1,0) [0|3] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + +BO_ 64 DATC14: 8 DATC + SG_ CF_Datc_AqsLevelOut : 0|4@1+ (1,0) [0|3] "" CLU + SG_ CF_Datc_DiagMode : 6|2@1+ (1,0) [0|3] "" CLU + SG_ CR_Datc_SelfDiagCode : 8|8@1+ (1,-1) [0|254] "" CLU + SG_ DATC_SyncDisp : 16|4@1+ (1,0) [0|3] "" CLU + SG_ DATC_OffDisp : 20|2@1+ (1,0) [0|3] "" CLU + SG_ DATC_SmartVentDisp : 22|2@1+ (1,0) [0|3] "" CLU + SG_ DATC_SmartVentOnOffStatus : 24|2@1+ (1,0) [0|3] "" CLU + SG_ DATC_AutoDefogSysOff_Disp : 26|2@1+ (1,0) [0|3] "" CLU + SG_ DATC_ADSDisp : 28|2@1+ (1,0) [0|3] "" CLU + +BO_ 832 LKAS11: 8 LDWS_LKAS + SG_ Byte0 : 0|8@1+ (1,0) [0|3] "" XXX + SG_ Byte1 : 8|8@1+ (1,0) [0|3] "" XXX + SG_ Byte2 : 16|8@1+ (1,0) [0|3] "" XXX + SG_ Byte3 : 24|8@1+ (1,0) [0|3] "" XXX + SG_ Byte4 : 32|8@1+ (1,0) [0|3] "" XXX + SG_ Byte5 : 40|8@1+ (1,0) [0|3] "" XXX + SG_ Byte6 : 48|8@1+ (1,0) [0|3] "" XXX + SG_ Byte7 : 56|8@1+ (1,0) [0|3] "" XXX + + + +BO_ 1342 LKAS12: 6 LDWS_LKAS + SG_ Byte0 : 0|8@1+ (1,0) [0|3] "" XXX + SG_ Byte1 : 8|8@1+ (1,0) [0|3] "" XXX + SG_ Byte2 : 16|8@1+ (1,0) [0|3] "" XXX + SG_ Byte3 : 24|8@1+ (1,0) [0|3] "" XXX + SG_ Byte4 : 32|8@1+ (1,0) [0|3] "" XXX + SG_ Byte5 : 40|8@1+ (1,0) [0|3] "" XXX + +BO_ 1338 TMU_GW_E_01: 8 CLU + SG_ CF_Gway_TeleReqDrLock : 0|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Gway_TeleReqDrUnlock : 2|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Gway_TeleReqHazard : 4|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Gway_TeleReqHorn : 6|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Gway_TeleReqEngineOperate : 8|2@1+ (1,0) [0|3] "" BCM + +BO_ 1078 PAS11: 4 BCM + SG_ CF_Gway_PASDisplayFLH : 0|3@1+ (1,0) [0|7] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayFRH : 3|3@1+ (1,0) [0|7] "" AVM,CLU,AVM + SG_ CF_Gway_PASRsound : 6|2@1+ (1,0) [0|3] "" CLU,Dummy + SG_ CF_Gway_PASDisplayFCTR : 8|3@1+ (1,0) [0|7] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayRCTR : 11|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASFsound : 14|2@1+ (1,0) [0|3] "" CLU,Dummy + SG_ CF_Gway_PASDisplayRLH : 16|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASDisplayRRH : 19|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASCheckSound : 22|2@1+ (1,0) [0|3] "" CLU,Dummy + SG_ CF_Gway_PASSystemOn : 24|2@1+ (1,0) [0|3] "" CLU,Dummy + SG_ CF_Gway_PASOption : 26|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_PASDistance : 28|1@1+ (1,0) [0|1] "" CLU + +BO_ 48 EMS18: 6 EMS + SG_ CF_Ems_DC1NumPerMSV : 0|8@1+ (1,0) [0|255] "" DI_BOX + SG_ CF_Ems_DC2NumPerMSV : 8|16@1+ (1,0) [0|65535] "" DI_BOX + SG_ CR_Ems_DutyCyc1MSV : 24|8@1+ (0.1953,0) [0|49.8] "%" DI_BOX + SG_ CR_Ems_DutyCyc2MSV : 32|8@1+ (0.13725,0) [0|35] "%" DI_BOX + SG_ CR_Ems_DutyCyc3MSV : 40|8@1+ (0.392,0) [0|100] "%" DI_BOX + +BO_ 1322 CLU15: 8 CLU + SG_ CF_Clu_VehicleSpeed : 0|8@1+ (1,0) [0|255] "" BCM + SG_ CF_Clu_InhibitP : 9|1@1+ (1,0) [0|1] "" BCM + SG_ CF_Clu_InhibitR : 10|1@1+ (1,0) [0|1] "" BCM + SG_ CF_Clu_InhibitN : 11|1@1+ (1,0) [0|1] "" BCM + SG_ CF_Clu_InhibitD : 12|1@1+ (1,0) [0|1] "" BCM + SG_ CF_Clu_HudInfoSet : 13|7@1+ (1,0) [0|127] "" HUD + SG_ CF_Clu_HudFontColorSet : 20|2@1+ (1,0) [0|3] "" HUD + SG_ CF_Clu_HudBrightUpSW : 22|2@1+ (1,0) [0|3] "" HUD + SG_ CF_Clu_HudBrightDnSW : 24|2@1+ (1,0) [0|3] "" HUD + SG_ CF_Clu_HudHeightUpSW : 26|2@1+ (1,0) [0|3] "" HUD + SG_ CF_Clu_HudHeightDnSW : 28|2@1+ (1,0) [0|3] "" HUD + SG_ CF_Clu_HudSet : 30|1@1+ (1,0) [0|1] "" HUD + SG_ CF_Clu_HudFontSizeSet : 31|2@1+ (1,0) [0|3] "" HUD + SG_ CF_Clu_LanguageInfo : 33|5@1+ (1,0) [0|31] "" BCM,PGS + SG_ CF_Clu_ClusterSound : 38|1@1- (1,0) [0|0] "" BCM,CGW,FATC + +BO_ 1066 _4WD13: 6 _4WD + SG_ _4WD_CURRENT : 0|8@1+ (0.390625,0) [-50|50] "A" TCU + SG_ _4WD_POSITION : 8|16@1+ (0.015625,0) [-180|180] "Deg" TCU + SG_ _4WD_CLU_THERM_STR : 24|8@1+ (1,0) [0|100] "%" TCU + SG_ _4WD_STATUS : 32|8@1+ (1,0) [0|15] "" ESC,TCU + +BO_ 1065 _4WD12: 8 _4WD + SG_ Ster_Pos : 0|16@1+ (1,-600) [-600|600] "Deg" ESC + SG_ FRSS : 16|8@1+ (1,0) [0|254] "km/h" ESC + SG_ FLSS : 24|8@1+ (1,0) [0|254] "km/h" ESC + SG_ RRSS : 32|8@1+ (1,0) [0|254] "km/h" ESC + SG_ RLSS : 40|8@1+ (1,0) [0|254] "km/h" ESC + SG_ CLU_PRES : 48|16@1+ (0.0625,-50) [-50|50] "Bar" ESC + +BO_ 809 EMS12: 8 EMS + SG_ TEMP_ENG : 8|8@1+ (0.75,-48) [-48|143.25] "deg" _4WD,BCM,CLU,DATC,EPB,ESC,IBOX,SMK,TCU + SG_ MAF_FAC_ALTI_MMV : 16|8@1+ (0.00781,0) [0|1.99155] "" IBOX,TCU + SG_ VB_OFF_ACT : 24|1@1+ (1,0) [0|1] "" IBOX,TCU + SG_ ACK_ES : 25|1@1+ (1,0) [0|1] "" _4WD,ACU,IBOX + SG_ CONF_MIL_FMY : 26|3@1+ (1,0) [0|7] "" ESC,IBOX,TCU + SG_ OD_OFF_REQ : 29|1@1+ (1,0) [0|1] "" IBOX,TCU + SG_ ACC_ACT : 30|1@1+ (1,0) [0|1] "" _4WD,ABS,CLU,ESC,IAP,IBOX,SCC,TCU + SG_ CLU_ACK : 31|1@1+ (1,0) [0|1] "" _4WD,EPB,ESC,IBOX + SG_ BRAKE_ACT : 32|2@1+ (1,0) [0|3] "" _4WD,ABS,ACU,AFLS,CLU,DATC,ECS,EPB,ESC,IBOX,LDWS_LKAS,TCU + SG_ ENG_CHR : 34|4@1+ (1,0) [0|15] "" _4WD,ABS,ACU,CLU,DATC,EPB,ESC,FATC,IBOX,SCC,SMK,TCU + SG_ GP_CTL : 38|2@1+ (1,0) [0|3] "" IBOX + SG_ TPS : 40|8@1+ (0.4694836,-15.0234742) [-15.0234742|104.6948357] "%" _4WD,ABS,ACU,CLU,DATC,ECS,EPB,ESC,IBOX,TCU + SG_ PV_AV_CAN : 48|8@1+ (0.3906,0) [0|99.603] "%" _4WD,AAF,ABS,ACU,AFLS,CLU,DATC,EPB,ESC,IAP,IBOX,LDWS_LKAS,SCC,TCU + SG_ ENG_VOL : 56|8@1+ (0.1,0) [0|25.5] "liter" _4WD,ABS,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,SCC,SMK + +BO_ 1064 _4WD11: 8 _4WD + SG_ _4WD_TYPE : 0|2@1+ (1,0) [0|3] "" ACU,ESC,TPMS + SG_ _4WD_SUPPORT : 2|2@1+ (1,0) [0|3] "" ABS,ESC,TPMS + SG_ _4WD_ERR : 8|8@1+ (1,0) [0|255] "" CLU,ESC + SG_ CLU_DUTY : 16|8@1+ (1,0) [0|64] "%" ABS,ESC + SG_ R_TIRE : 24|8@1+ (1,200) [200|455] "mm" ABS,ESC,TPMS + SG_ _4WD_SW : 32|8@1+ (1,0) [0|9.9] "" ESC + SG_ _2H_ACT : 40|1@1+ (1,0) [0|1] "" ABS,ESC + SG_ _4H_ACT : 41|1@1+ (1,0) [0|1] "" ABS,CLU,ESC,TPMS + SG_ LOW_ACT : 42|1@1+ (1,0) [0|1] "" ABS,ESC,TCU,TPMS + SG_ AUTO_ACT : 43|1@1+ (1,0) [0|1] "" ABS,ESC,TPMS + SG_ LOCK_ACT : 44|1@1+ (1,0) [0|1] "" ABS,CLU,ESC,TPMS + SG_ _4WD_TQC_CUR : 48|16@1+ (1,0) [0|65535] "Nm" ABS,ESC + +BO_ 1319 HU_GW_E_01: 8 CLU + SG_ C_ADrLNValueSet : 0|3@1+ (1,0) [0|7] "" BCM + SG_ C_ADrUNValueSet : 4|3@1+ (1,0) [0|7] "" BCM + SG_ C_TwUnNValueSet : 8|2@1+ (1,0) [0|3] "" BCM + SG_ C_ABuzzerNValueSet : 10|2@1+ (1,0) [0|3] "" BCM + SG_ C_ArmWKeyNValueSet : 12|2@1+ (1,0) [0|3] "" BCM + SG_ C_PSMNValueSet : 14|2@1+ (1,0) [0|3] "" BCM + SG_ C_SCMNValueSet : 16|2@1+ (1,0) [0|3] "" BCM + SG_ C_HLEscortNValueSet : 18|2@1+ (1,0) [0|3] "" BCM + SG_ C_WELNValueSet : 20|2@1+ (1,0) [0|3] "" BCM + SG_ C_TriTurnLNValueSet : 22|2@1+ (1,0) [0|3] "" BCM + SG_ C_SNVWarnNValueSet : 24|2@1+ (1,0) [0|3] "" BCM + SG_ C_LkasWarnNValueSet : 26|2@1+ (1,0) [0|3] "" BCM + +BO_ 1318 HU_GW_E_00: 8 CLU + SG_ C_ADrLURValueReq : 0|2@1+ (1,0) [0|3] "" BCM + SG_ C_TwUnRValueReq : 2|2@1+ (1,0) [0|3] "" BCM + SG_ C_AlarmRValueReq : 4|2@1+ (1,0) [0|3] "" BCM + SG_ C_IMSRValueReq : 6|2@1+ (1,0) [0|3] "" BCM + SG_ C_HLEscortRValueReq : 8|2@1+ (1,0) [0|3] "" BCM + SG_ C_WELRValueReq : 10|2@1+ (1,0) [0|3] "" BCM + SG_ C_TriTurnLRValueReq : 12|2@1+ (1,0) [0|3] "" BCM + SG_ C_SNVWarnRValueReq : 14|2@1+ (1,0) [0|3] "" BCM + SG_ C_LkasWarnRValueReq : 16|2@1+ (1,0) [0|3] "" BCM + +BO_ 1317 GW_HU_E_01: 8 BCM + SG_ C_ADrLRValue : 0|3@1+ (1,0) [0|7] "" CLU + SG_ C_ADrURValue : 4|3@1+ (1,0) [0|7] "" CLU + SG_ C_TwUnRValue : 8|2@1+ (1,0) [0|3] "" CLU + SG_ C_ABuzzerRValue : 10|2@1+ (1,0) [0|3] "" CLU + SG_ C_ArmWKeyRValue : 12|2@1+ (1,0) [0|3] "" CLU + SG_ C_PSMRValue : 14|2@1+ (1,0) [0|3] "" CLU + SG_ C_SCMRValue : 16|2@1+ (1,0) [0|3] "" CLU + SG_ C_HLEscortRValue : 18|2@1+ (1,0) [0|3] "" CLU + SG_ C_WELRValue : 20|2@1+ (1,0) [0|3] "" CLU + SG_ C_TriTurnLRValue : 22|2@1+ (1,0) [0|3] "" CLU + +BO_ 1316 GW_HU_E_00: 8 BCM + SG_ C_ADrLUNValueConf : 0|2@1+ (1,0) [0|3] "" CLU + SG_ C_TwUnNValueConf : 2|2@1+ (1,0) [0|3] "" CLU + SG_ C_AlarmNValueConf : 4|2@1+ (1,0) [0|3] "" CLU + SG_ C_PSMNValueConf : 6|2@1+ (1,0) [0|3] "" CLU + SG_ C_SCMNValueConf : 8|2@1+ (1,0) [0|3] "" CLU + SG_ C_HLEscortNValueConf : 10|2@1+ (1,0) [0|3] "" CLU + SG_ C_WELNValueConf : 12|2@1+ (1,0) [0|3] "" CLU + SG_ C_TriTurnLNValueConf : 14|2@1+ (1,0) [0|3] "" CLU + +BO_ 1315 GW_SWRC_PE: 8 BCM + SG_ C_ModeSW : 2|2@1+ (1,0) [0|3] "" CLU + SG_ C_MuteSW : 4|2@1+ (1,0) [0|3] "" CLU + SG_ C_SeekDnSW : 6|2@1+ (1,0) [0|3] "" CLU + SG_ C_SeekUpSW : 8|2@1+ (1,0) [0|3] "" CLU + SG_ C_BTPhoneCallSW : 10|2@1+ (1,0) [0|3] "" CLU + SG_ C_BTPhoneHangUpSW : 12|2@1+ (1,0) [0|3] "" CLU + SG_ C_DISCDownSW : 14|2@1+ (1,0) [0|3] "" CLU + SG_ C_DISCUpSW : 16|2@1+ (1,0) [0|3] "" CLU + SG_ C_SdsSW : 18|2@1+ (1,0) [0|3] "" CLU + SG_ C_MTSSW : 20|2@1+ (1,0) [0|3] "" CLU + SG_ C_VolDnSW : 22|2@1+ (1,0) [0|3] "" CLU + SG_ C_VolUpSW : 24|2@1+ (1,0) [0|3] "" CLU + +BO_ 1314 GW_IPM_PE_1: 8 BCM + SG_ C_AV_Tail : 0|2@1+ (1,0) [0|3] "" CLU + SG_ C_ParkingBrakeSW : 2|2@1+ (1,0) [0|3] "" CLU + SG_ C_RKECMD : 4|4@1+ (1,0) [0|15] "" CLU + SG_ C_BAState : 8|2@1+ (1,0) [0|3] "" CLU + SG_ C_IGNSW : 12|3@1+ (1,0) [0|7] "" CLU + SG_ C_CountryCfg : 16|3@1+ (1,0) [0|7] "" CLU + SG_ C_TailLampActivity : 26|2@1+ (1,0) [0|3] "" CLU + SG_ RearSW_RSELockOnOff : 28|2@1+ (1,0) [0|3] "" CLU + SG_ C_SMKTeleCrankingState : 32|2@1+ (1,0) [0|3] "" CLU + SG_ C_SMKTeleCrankingFailRes : 34|2@1+ (1,0) [0|3] "" CLU + +BO_ 1057 SCC12: 8 SCC + SG_ CF_VSM_Prefill : 0|1@1+ (1,0) [0|1] "" ESC + SG_ CF_VSM_DecCmdAct : 1|1@1+ (1,0) [0|1] "" ESC + SG_ CF_VSM_HBACmd : 2|2@1+ (1,0) [0|3] "" ESC + SG_ CF_VSM_Warn : 4|2@1+ (1,0) [0|3] "" CLU,ESC,IAP + SG_ CF_VSM_Stat : 6|2@1+ (1,0) [0|3] "" CLU,ESC,PSB + SG_ CF_VSM_BeltCmd : 8|3@1+ (1,0) [0|7] "" ESC,PSB + SG_ ACCFailInfo : 11|2@1+ (1,0) [0|3] "" CLU,CUBIS,ESC,IBOX + SG_ ACCMode : 13|2@1+ (1,0) [0|3] "" CLU,ESC,IBOX,TCU + SG_ StopReq : 15|1@1+ (1,0) [0|1] "" EPB,ESC + SG_ CR_VSM_DecCmd : 16|8@1+ (0.01,0) [0|2.55] "g" ESC + SG_ aReqMax : 24|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ TakeOverReq : 35|1@1+ (1,0) [0|1] "" CLU,ESC,TCU + SG_ PreFill : 36|1@1+ (1,0) [0|1] "" ESC,TCU + SG_ aReqMin : 37|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ CF_VSM_ConfMode : 48|2@1+ (1,0) [0|3] "" CLU,ESC + SG_ AEB_Failinfo : 50|2@1+ (1,0) [0|3] "" CLU,ESC + SG_ AEB_Status : 52|2@1+ (1,0) [0|3] "" CLU,ESC + SG_ AEB_CmdAct : 54|1@1+ (1,0) [0|1] "" ESC + SG_ AEB_StopReq : 55|1@1+ (1,0) [0|1] "" CLU,ESC + SG_ CR_VSM_Alive : 56|4@1+ (1,0) [0|15] "" ESC,PSB + SG_ CR_VSM_ChkSum : 60|4@1+ (1,0) [0|15] "" ESC,PSB + +BO_ 1313 GW_DDM_PE: 8 BCM + SG_ C_DRVDoorStatus : 0|2@1+ (1,0) [0|3] "" CLU + SG_ C_ASTDoorStatus : 2|2@1+ (1,0) [0|3] "" CLU + SG_ C_RLDoorStatus : 4|2@1+ (1,0) [0|3] "" CLU + SG_ C_RRDoorStatus : 6|2@1+ (1,0) [0|3] "" CLU + SG_ C_TrunkStatus : 8|2@1+ (1,0) [0|3] "" CLU + SG_ C_OSMirrorStatus : 10|2@1+ (1,0) [0|3] "" 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 + SG_ AliveCounterACC : 4|4@1+ (1,0) [0|15] "" CLU,EMS,ESC,TCU + SG_ VSetDis : 8|8@1+ (1,0) [0|255] "km/h or MPH" CLU,ESC,TCU + SG_ ObjValid : 16|1@1+ (1,0) [0|1] "" CLU,ESC,TCU + SG_ DriverAlertDisplay : 17|2@1+ (1,0) [0|3] "" CLU,ESC + SG_ TauGapSet : 19|3@1+ (1,0) [0|7] "" CLU,ESC,TCU + SG_ ACC_ObjStatus : 22|2@1+ (1,0) [0|3] "" ABS,ESC + SG_ ACC_ObjLatPos : 24|9@1+ (0.1,-20) [-20|31.1] "m" ABS,ESC + SG_ ACC_ObjDist : 33|11@1+ (0.1,0) [0|204.7] "m" ABS,ESC + SG_ ACC_ObjRelSpd : 44|12@1+ (0.1,-170) [-170|239.5] "m/s" ABS,ESC + SG_ Navi_SCC_Curve_Status : 56|2@1+ (1,0) [0|3] "" CLU + SG_ Navi_SCC_Curve_Act : 58|2@1+ (1,0) [0|3] "" CLU + SG_ Navi_SCC_Camera_Act : 60|2@1+ (1,0) [0|3] "" CLU + SG_ Navi_SCC_Camera_Status : 62|2@1+ (1,0) [0|3] "" CLU + +BO_ 1312 CGW3: 8 BCM + SG_ CR_Photosensor_LH : 0|8@1+ (78.125,0) [0|20000] "" DATC,DATC + SG_ CR_Photosensor_RH : 10|8@1+ (78.125,0) [0|20000] "" DATC,DATC + SG_ CF_Hoodsw_memory : 22|2@1+ (1,0) [0|3] "" EMS,EMS + SG_ C_MirOutTempSns : 24|8@1+ (0.5,-40.5) [-40|60] "deg" AAF,CLU,DATC,EMS,SPAS,AAF,DATC,EMS,SPAS + +BO_ 544 ESP12: 8 ESC + SG_ LAT_ACCEL : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_STAT : 11|1@1+ (1,0) [0|1] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_DIAG : 12|1@1+ (1,0) [0|1] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LONG_ACCEL : 13|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_STAT : 24|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_DIAG : 25|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ CYL_PRES : 26|12@1+ (0.1,0) [0|409.5] "Bar" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRES_STAT : 38|1@1+ (1,0) [0|1] "" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRESS_DIAG : 39|1@1+ (1,0) [0|1] "" _4WD,ECS,EMS,EPB,IBOX,PSB,SCC,TCU + SG_ YAW_RATE : 40|13@1+ (0.01,-40.95) [-40.95|40.96] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_STAT : 53|1@1+ (1,0) [0|1] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_DIAG : 54|1@1+ (1,0) [0|1] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ ESP12_AliveCounter : 56|4@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU + SG_ ESP12_Checksum : 60|4@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1307 CLU16: 8 CLU + SG_ CF_Clu_TirePressUnitNValueSet : 0|3@1+ (1,0) [0|7] "" TPMS + SG_ CF_Clu_SlifNValueSet : 3|2@1+ (1,0) [0|3] "" LDWS_LKAS + SG_ CF_Clu_RearWiperNValueSet : 12|2@1+ (1,0) [0|3] "" BCM + +BO_ 790 EMS11: 8 EMS + SG_ SWI_IGK : 0|1@1+ (1,0) [0|1] "" _4WD,ABS,ACU,AHLS,CUBIS,DI_BOX,ECS,EPB,ESC,IBOX,LDWS_LKAS,MDPS,REA,SAS,SCC,TCU + SG_ F_N_ENG : 1|1@1+ (1,0) [0|1] "" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,IBOX,MDPS,SCC,TCU + SG_ ACK_TCS : 2|1@1+ (1,0) [0|1] "" ESC,IBOX + SG_ PUC_STAT : 3|1@1+ (1,0) [0|1] "" _4WD,CLU,DATC,IBOX,TCU + SG_ TQ_COR_STAT : 4|2@1+ (1,0) [0|3] "" _4WD,ESC,IBOX,TCU + SG_ RLY_AC : 6|1@1+ (1,0) [0|1] "" DATC,IBOX,TCU + SG_ F_SUB_TQI : 7|1@1+ (1,0) [0|1] "" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQI_ACOR : 8|8@1+ (0.390625,0) [0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ N : 16|16@1+ (0.25,0) [0|16383.75] "rpm" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,FPCM,IBOX,MDPS,SCC,TCU + SG_ TQI : 32|8@1+ (0.390625,0) [0|99.6094] "%" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ VS : 48|8@1+ (1,0) [0|254] "km/h" _4WD,AAF,ACU,AHLS,BCM,CLU,DATC,ECS,EPB,IBOX,LCA,LDWS_LKAS,LVR,MDPS,ODS,SCC,SMK,SPAS,TCU,TPMS + SG_ RATIO_TQI_BAS_MAX_STND : 56|8@1+ (0.0078,0) [0|2] "" _4WD,IBOX,TCU + +BO_ 1301 CLU14: 8 CLU + SG_ CF_Clu_ADrUNValueSet : 0|3@1+ (1,0) [0|7] "" BCM + SG_ CF_Clu_ADrLNValueSet : 3|3@1+ (1,0) [0|7] "" BCM + SG_ CF_Clu_EscortHLNValueSet : 6|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Clu_DoorLSNValueSet : 8|3@1+ (1,0) [0|7] "" BCM + SG_ CF_Clu_PSMNValueSet : 11|3@1+ (1,0) [0|7] "" BCM + SG_ CF_Clu_TTUnlockNValueSet : 14|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Clu_PTGMNValueSet : 16|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Clu_SCMNValueSet : 18|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Clu_WlightNValueSet : 20|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Clu_TempUnitNValueSet : 22|2@1+ (1,0) [0|3] "" BCM,DATC + SG_ CF_Clu_MoodLpNValueSet : 24|3@1+ (1,0) [0|7] "" BCM + SG_ CF_Clu_TrfChgSet : 27|2@1+ (1,0) [0|3] "" AFLS + SG_ CF_Clu_OTTurnNValueSet : 29|3@1+ (1,0) [0|7] "" BCM + SG_ CF_Clu_LcaNValueSet : 32|2@1+ (1,0) [0|3] "" LCA + SG_ CF_Clu_RctaNValueSet : 34|2@1+ (1,0) [0|3] "" LCA + SG_ CF_Clu_RcwNValueSet : 36|2@1+ (1,0) [0|3] "" LCA + SG_ CF_Clu_EscOffNValueSet : 38|3@1+ (1,0) [0|7] "" ESC + SG_ CF_Clu_SccNaviCrvNValueSet : 41|2@1+ (1,0) [0|3] "" SCC + SG_ CF_Clu_SccNaviCamNValueSet : 43|2@1+ (1,0) [0|3] "" SCC + SG_ CF_Clu_SccAebNValueSet : 45|2@1+ (1,0) [0|3] "" SCC + SG_ CF_Clu_LkasModeNValueSet : 47|2@1+ (1,0) [0|3] "" LDWS_LKAS + SG_ CF_Clu_FcwNValueSet : 51|2@1+ (1,0) [0|3] "" LDWS_LKAS + SG_ CF_Clu_PasSpkrLvNValueSet : 53|3@1+ (1,0) [0|7] "" BCM + SG_ CF_Clu_SccDrvModeNValueSet : 56|3@1+ (1,0) [0|7] "" SCC + SG_ CF_Clu_HAnBNValueSet : 59|2@1+ (1,0) [0|3] "" BCM + SG_ CF_Clu_HfreeTrunkTgNValueSet : 61|3@1+ (1,0) [0|7] "" BCM + +BO_ 275 TCU13: 8 TCU + SG_ N_TGT_LUP : 0|8@1+ (10,500) [500|3040] "rpm" EMS,IBOX + SG_ SLOPE_TCU : 8|6@1+ (0.5,-16) [-16|15.5] "%" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhCda : 14|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Tcu_IsgInhib : 15|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Tcu_BkeOnReq : 16|2@1+ (1,0) [0|3] "" EMS,IBOX + SG_ CF_Tcu_NCStat : 18|2@1+ (1,0) [0|3] "" EMS,IBOX + SG_ CF_Tcu_TarGr : 20|4@1+ (1,0) [0|15] "" _4WD,CLU,DATC,EMS,EPB,ESC,IBOX,SCC + SG_ CF_Tcu_ShfPatt : 24|4@1+ (1,0) [0|15] "" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhVis : 28|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Tcu_PRelReq : 29|1@1+ (1,0) [0|1] "" IBOX,LVR + SG_ CF_Tcu_ITPhase : 30|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Tcu_ActEcoRdy : 31|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Tcu_TqGrdLim : 32|8@1+ (10,0) [0|2540] "Nm/s" EMS,IBOX + SG_ CR_Tcu_IsgTgtRPM : 40|8@1+ (20,0) [0|3500] "rpm" EMS,IBOX + SG_ CF_Tcu_SptRdy : 48|1@1+ (1,0) [0|1] "" CLU,IBOX + SG_ CF_Tcu_SbwPInfo : 56|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ CF_Tcu_Alive3 : 58|2@1+ (1,0) [0|3] "" EMS,IBOX + SG_ CF_Tcu_ChkSum3 : 60|4@1+ (1,0) [0|15] "" EMS,IBOX + +BO_ 274 TCU12: 8 TCU + SG_ ETL_TCU : 0|8@1+ (2,0) [0|508] "Nm" EMS,IBOX + SG_ CUR_GR : 8|4@1+ (1,0) [0|15] "" _4WD,EMS,ESC,IBOX,SCC,TPMS + SG_ CF_Tcu_Alive : 12|2@1+ (1,0) [0|3] "" EMS,ESC,IBOX,SCC + SG_ CF_Tcu_ChkSum : 14|2@1+ (1,0) [0|3] "" EMS,ESC,IBOX,SCC + SG_ VS_TCU : 16|8@1+ (1,0) [0|254] "km/h" BCM,CLU,DATC,EMS,IBOX,LCA,LVR,PGS,SMK,SNV + SG_ FUEL_CUT_TCU : 28|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ INH_FUEL_CUT : 29|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ IDLE_UP_TCU : 30|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ N_INC_TCU : 31|1@1+ (1,0) [0|1] "" EMS,IBOX + SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15|15] "" EMS,IBOX + SG_ N_TC_RAW : 40|16@1+ (0.25,0) [0|16383.5] "rpm" EMS,IBOX + SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0) [0|0.9921875] "km/h" CLU,EMS,IBOX,LCA + +BO_ 273 TCU11: 8 TCU + SG_ TQI_TCU_INC : 0|8@1+ (0.390625,0) [0|99.609375] "%" EMS,ESC,IBOX + SG_ G_SEL_DISP : 8|4@1+ (1,0) [0|15] "" _4WD,AFLS,AVM,BCM,CGW,CLU,CUBIS,ECS,EMS,EPB,ESC,IAP,IBOX,LCA,LDWS_LKAS,LVR,MDPS,PGS,SCC,SMK,SNV,SPAS,TPMS + SG_ F_TCU : 12|2@1+ (1,0) [0|3] "" EMS,ESC,IBOX + SG_ TCU_TYPE : 14|2@1+ (1,0) [0|3] "" _4WD,EMS,ESC,IBOX + SG_ TCU_OBD : 16|3@1+ (1,0) [0|7] "" EMS,ESC,IBOX + SG_ SWI_GS : 19|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,ESC,IBOX,SCC + SG_ GEAR_TYPE : 20|4@1+ (1,0) [0|15] "" _4WD,CLU,EMS,ESC,IBOX,SCC + SG_ TQI_TCU : 24|8@1+ (0.390625,0) [0|99.609375] "%" EMS,ESC,IBOX + SG_ TEMP_AT : 32|8@1+ (1,-40) [-40|214] "deg" AAF,CLU,CUBIS,EMS,ESC,IBOX + SG_ N_TC : 40|16@1+ (0.25,0) [0|16383.5] "rpm" _4WD,EMS,EPB,ESC,IBOX + SG_ SWI_CC : 56|2@1+ (1,0) [0|3] "" _4WD,CLU,EMS,ESC,IBOX + SG_ CF_Tcu_Alive1 : 58|2@1+ (1,0) [0|3] "" EMS,IBOX + SG_ CF_Tcu_ChkSum1 : 60|4@1+ (1,0) [0|15] "" EMS,IBOX + +BO_ 16 ACU13: 8 ACU + SG_ CF_Acu_CshAct : 0|1@1+ (1,0) [0|1] "" CUBIS,IBOX,ODS + +BO_ 1040 CGW_USM1: 8 BCM + SG_ CF_Gway_ATTurnRValue : 0|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_PTGMRValue : 2|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_EscortHLRValue : 4|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_TTUnlockRValue : 6|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_ADrLRValue : 8|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_ADrURValue : 11|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_SCMRValue : 14|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_WlightRValue : 16|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_PSMRValue : 18|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_OTTurnRValue : 21|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_DrLockSoundRValue : 24|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_HAnBRValue : 27|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_MoodLpRValue : 30|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_HfreeTrunkRValue : 32|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_AutoLightRValue : 35|3@1+ (1,0) [0|7] "" CLU + SG_ CF_Gway_RearWiperRValue : 38|2@1+ (1,0) [0|3] "" CLU + SG_ CF_Gway_PasSpkrLvRValue : 40|3@1+ (1,0) [0|7] "" CLU + +BO_ 1292 CLU13: 8 CLU + SG_ CF_Clu_LowfuelWarn : 0|2@1+ (1,0) [0|3] "" BCM,FPCM,IBOX + SG_ CF_Clu_RefDetMod : 2|1@1+ (1,0) [0|1] "" IBOX + SG_ CF_Clu_AvgFCU : 3|2@1+ (1,0) [0|3] "" IBOX + SG_ CF_Clu_AvsmCur : 5|1@1+ (1,0) [0|1] "" ESC,SCC + SG_ CF_Clu_AvgFCI : 6|10@1+ (0.1,0) [0|102.2] "" IBOX + SG_ CF_Clu_DrivingModeSwi : 16|2@1+ (1,0) [0|3] "" DATC,ECS,EMS,ESC,IAP,MDPS,TCU + SG_ CF_Clu_FuelDispLvl : 18|5@1+ (1,0) [0|31] "" CGW,IBOX + SG_ CF_Clu_FlexSteerSW : 23|1@1+ (1,0) [0|1] "" MDPS + SG_ CF_Clu_DTE : 24|10@1+ (1,0) [0|1023] "" DATC + SG_ CF_Clu_TripUnit : 34|2@1+ (1,0) [0|3] "" DATC + SG_ CF_Clu_SWL_Stat : 36|3@1+ (1,0) [0|7] "" ACU,EMS + SG_ CF_Clu_ActiveEcoSW : 39|1@1+ (1,0) [0|1] "" DATC,EMS,TCU + SG_ CF_Clu_EcoDriveInf : 40|3@1+ (1,0) [0|7] "" CUBIS,EMS,IAP,IBOX + SG_ CF_Clu_IsaMainSW : 43|1@1+ (1,0) [0|1] "" EMS + SG_ CF_Clu_LdwsLkasSW : 56|1@1+ (1,0) [0|1] "" LDWS_LKAS + SG_ CF_Clu_AltLStatus : 59|1@1+ (1,0) [0|1] "" BCM,DATC,EMS + SG_ CF_Clu_AliveCnt2 : 60|4@1+ (1,0) [0|15] "" EMS,LDWS_LKAS + +BO_ 1290 SCC13: 8 SCC + SG_ SCCDrvModeRValue : 0|3@1+ (1,0) [0|7] "" CLU + SG_ SCC_Equip : 3|1@1+ (1,0) [0|1] "" ESC + SG_ AebDrvSetStatus : 4|3@1+ (1,0) [0|7] "" CLU,ESC + +BO_ 1287 TCS15: 4 ESC + SG_ ABS_W_LAMP : 0|1@1+ (1,0) [0|1] "" _4WD,CLU,CUBIS,IBOX + SG_ TCS_OFF_LAMP : 1|2@1+ (1,0) [0|1] "" _4WD,ACU,CLU + SG_ TCS_LAMP : 3|2@1+ (1,0) [0|3] "" _4WD,ACU,CLU,CUBIS,IBOX,SCC + SG_ DBC_W_LAMP : 5|1@1+ (1,0) [0|1] "" _4WD,CLU + SG_ DBC_F_LAMP : 6|2@1+ (1,0) [0|3] "" _4WD,CLU + SG_ ESC_Off_Step : 8|2@1+ (1,0) [0|3] "" CLU + SG_ AVH_CLU : 16|8@1+ (1,0) [0|255] "" CLU,EPB + SG_ AVH_I_LAMP : 24|2@1+ (1,0) [0|3] "" EPB + SG_ EBD_W_LAMP : 26|1@1+ (1,0) [0|1] "" _4WD,CLU + SG_ AVH_ALARM : 27|2@1+ (1,0) [0|3] "" CLU + SG_ AVH_LAMP : 29|3@1+ (1,0) [0|7] "" CLU,EPB,SPAS + +BO_ 1282 TCU14: 4 TCU + SG_ CF_TCU_WarnMsg : 0|3@1+ (1,0) [0|7] "" CLU + SG_ CF_TCU_WarnImg : 3|1@1+ (1,0) [0|1] "" CLU + SG_ CF_TCU_WarnSnd : 4|1@1+ (1,0) [0|1] "" CLU + SG_ CF_Tcu_GSel_BlinkReq : 5|1@1+ (1,0) [0|1] "" CLU,LVR + SG_ CF_Tcu_StRelStat : 12|1@1+ (1,0) [0|1] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn1 : 13|3@1+ (1,0) [0|7] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn2 : 16|2@1+ (1,0) [0|3] "" CLU,EMS,ESC + +BO_ 1281 ECS11: 3 ECS + SG_ ECS_W_LAMP : 0|1@1+ (1,0) [0|1] "" CLU,CUBIS,IBOX + SG_ SYS_NA : 1|1@1+ (1,0) [0|1] "" CLU + SG_ ECS_DEF : 2|1@1+ (1,0) [0|1] "" CLU + SG_ ECS_DIAG : 3|1@1+ (1,0) [0|1] "" CLU + SG_ L_CHG_NA : 4|1@1+ (1,0) [0|1] "" CLU + SG_ Leveling_Off : 5|1@1+ (1,0) [0|1] "" CLU + SG_ LC_overheat : 6|1@1+ (1,0) [0|1] "" CLU + SG_ Lifting : 8|1@1+ (1,0) [0|1] "" CLU + SG_ Lowering : 9|1@1+ (1,0) [0|1] "" CLU + SG_ Damping_Mode : 10|2@1+ (1,0) [0|3] "" CLU + SG_ REQ_Damping : 12|2@1+ (1,0) [0|3] "" CLU + SG_ REQ_Height : 14|2@1+ (1,0) [0|3] "" CLU + SG_ REQ_level : 16|4@1+ (1,0) [0|15] "" CLU + SG_ ACT_Height : 20|4@1+ (1,0) [0|15] "" CLU + +BO_ 1024 CLU_CFG11: 2 CLU + SG_ Vehicle_Type : 0|16@1+ (1,0) [0|65536] "" _4WD + +BO_ 1280 ACU14: 1 ACU + SG_ CF_SWL_Ind : 0|2@1+ (1,0) [0|3] "" CLU + SG_ CF_TTL_Ind : 2|2@1+ (1,0) [0|3] "" CLU + SG_ CF_SBR_Ind : 4|2@1+ (1,0) [0|3] "" BCM,CLU + +BO_ 512 EMS20: 6 EMS + SG_ FCO : 0|16@1+ (0.128,0) [0|8388.48] "ul" CLU,CUBIS,FPCM,IBOX + SG_ CF_Ems_PumpTPres : 16|8@1+ (3.137254902,0) [0|800] "kPa" FPCM,IBOX + SG_ Split_Stat : 32|1@1+ (1,0) [0|1] "" FPCM + +BO_ 872 AT01: 8 XXX + SG_ Gear : 32|4@1+ (1,0) [0|15] "" XXX diff --git a/opendbc/toyota_rav4_2017_pt.dbc b/opendbc/lexus_is_2018_pt_generated.dbc similarity index 57% rename from opendbc/toyota_rav4_2017_pt.dbc rename to opendbc/lexus_is_2018_pt_generated.dbc index 178ce26f5a1191..c0522bec2ccbed 100644 --- a/opendbc/toyota_rav4_2017_pt.dbc +++ b/opendbc/lexus_is_2018_pt_generated.dbc @@ -1,3 +1,35 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" VERSION "" @@ -57,15 +89,12 @@ BO_ 180 SPEED: 8 XXX BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 548 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX - SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX - BO_ 552 ACCELEROMETER: 8 XXX SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX @@ -73,39 +102,25 @@ BO_ 552 ACCELEROMETER: 8 XXX BO_ 560 BRAKE_MODULE2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX -BO_ 705 GAS_PEDAL: 8 XXX - SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 643 PRE_COLLISION: 8 XXX -BO_ 740 STEERING_LKA: 8 XXX +BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX BO_ 742 LEAD_INFO: 8 DSU SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU @@ -114,6 +129,11 @@ 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_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 1556 STEERING_LEVERS: 8 XXX SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX @@ -132,29 +152,34 @@ BO_ 467 PCM_CRUISE_2: 8 XXX BO_ 921 PCM_CRUISE_SM: 8 XXX SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX BO_ 951 ESP_CONTROL: 8 ESP SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX BO_ 1042 LKAS_HUD: 8 XXX SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX BO_ 1553 UI_SEETING: 8 XXX SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX @@ -166,16 +191,46 @@ BO_ 1568 SEATS_DOORS: 8 XXX SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX CM_ SG_ 36 ACCEL_Y "unit is tbd"; CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 560 BRAKE_PRESSED "another brake press?"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; @@ -186,11 +241,9 @@ CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disenga CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +CM_ SG_ 1161 SPDVAL1 "is the displayed speed 10,30,50,60,70,80,90,100,120 and 255 is for no limit. SPDVAL2 is the secondary speed usually written smaller"; VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ; VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; -VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 50 "temporary_fault"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 1553 UNITS 1 "km" 2 "miles"; @@ -202,3 +255,44 @@ VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "lexus_is_2018_pt.dbc starts here" + + + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +BO_ 1009 PCM_CRUISE_3: 8 XXX + SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX + SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc new file mode 100644 index 00000000000000..94ca42f816d344 --- /dev/null +++ b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc @@ -0,0 +1,323 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "lexus_rx_hybrid_2017_pt.dbc starts here" + + + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 5 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/opendbc/mercedes_benz_e350_2010.dbc b/opendbc/mercedes_benz_e350_2010.dbc index 9841af6d4f8952..da6ae4c15ee66b 100644 --- a/opendbc/mercedes_benz_e350_2010.dbc +++ b/opendbc/mercedes_benz_e350_2010.dbc @@ -36,27 +36,141 @@ BS_: BU_: XXX -BO_ 3 NEW_MSG_1: 8 XXX - SG_ STEERING_ANGLE : 7|32@0- (1,0) [0|4294967295] "" XXX - SG_ NEW_SIGNAL_1 : 55|8@0+ (1,0) [0|255] "" XXX +BO_ 3 STEER_SENSOR: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_RATE : 19|12@0- (0.5,0) [0|255] "" XXX + SG_ STEER_DIRECTION : 4|1@0+ (1,2) [0|1] "" XXX + SG_ STEER_ANGLE : 3|12@0- (-0.5,0) [-500|500] "degrees" XXX -BO_ 5 NEW_MSG_2: 8 XXX - SG_ BRAKE_POSITION : 23|16@0+ (1,0) [0|65535] "" XXX - SG_ BRAKE_PRESSED : 0|8@1+ (1,0) [0|17] "" XXX +BO_ 5 BRAKE_MODULE: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_HOLD : 2|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_POSITION : 17|10@0+ (1,0) [0|65535] "" XXX + SG_ DRIVER_BRAKE : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COMPUTER_BRAKE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_PRESSED : 0|1@1+ (1,0) [0|1] "" XXX -BO_ 69 NEW_MSG_3: 8 XXX - SG_ TURN_SIGNAL_LEVER : 16|8@1+ (1,0) [0|255] "" XXX - SG_ CRUISE_CONTROL_LEVER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_2 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_1 : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEERING_WHEEL_BUTTONS : 32|8@1+ (1,0) [0|255] "4 directional, 2 volume control, & 2 phone buttons" XXX - SG_ MORE_STEERING_WHEELS_BUTTONS : 40|8@1+ (1,0) [0|255] "" XXX +BO_ 69 DRIVER_CONTROLS: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ STEERING_WHEEL_BUTTONS : 32|16@1+ (1,0) [0|255] "4 directional, 2 volume control & 2 phone buttons" XXX + SG_ LEFT_BLINKER : 16|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_BLINKER : 17|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAM_TOGGLE : 18|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAM_MOMENTARY : 19|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_CANCEL : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_RESUME : 1|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_ACCEL_HIGH : 2|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_DECEL_HIGH : 3|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_ACCEL_LOW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_DECEL_LOW : 5|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XFF : 15|8@0+ (1,0) [0|255] "" XXX -BO_ 1 NEW_MSG_4: 8 XXX - SG_ DOOR_LOCK_STATUS : 31|16@0+ (1,0) [0|65535] "" XXX +BO_ 513 WHEEL_ENCODERS: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ WHEEL_ENCODER_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_ENCODER_3 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_ENCODER_4 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 56|8@1+ (1,0) [0|255] "" XXX + SG_ WHEEL_ENCODER_1 : 7|8@0+ (1,0) [0|255] "" XXX +BO_ 261 GAS_PEDAL: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ENGINE_RPM : 4|5@0+ (1,0) [0|255] "" XXX + SG_ GAS_PEDAL : 39|8@0+ (1,0) [0|255] "" XXX + SG_ COMBINED_GAS : 31|8@0+ (1,0) [0|255] "" XXX +BO_ 643 DOOR_SENSORS: 8 XXX + SG_ BRAKE_PRESSED : 27|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 3|1@1+ (1,0) [0|3] "" XXX + SG_ DOOR_OPEN_RL : 5|1@0+ (1,0) [0|3] "" XXX + SG_ DOOR_OPEN_RR : 7|1@0+ (1,0) [0|3] "" XXX + SG_ DOOR_OPEN_FL : 1|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_FL : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_FR : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_RL : 4|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_RR : 6|1@0+ (1,0) [0|1] "" XXX +BO_ 885 SEATBELT_SENSORS: 8 XXX + SG_ SEATBELT_DRIVER_LATCHED : 16|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_PASSENGER_LATCHED : 18|1@0+ (1,0) [0|1] "" XXX -CM_ SG_ 5 BRAKE_PRESSED "appears to be boolean (brake pressed)"; -CM_ SG_ 69 MORE_STEERING_WHEELS_BUTTONS "back, ok, voice assistance, and mute buttons"; +BO_ 257 CRUISE_CONTROL: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 6|1@0+ (1,0) [0|255] "" XXX + SG_ CRUISE_DISABLED : 23|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X002 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X003 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_1 : 5|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACCELERATING : 22|1@0+ (1,0) [0|1] "" XXX + SG_ LONGITUDINAL_ACCEL_REQUEST : 15|8@0- (1,0) [0|127] "" XXX + +BO_ 260 CRUISE_CONTROL2: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XFF : 31|8@0+ (1,0) [0|65535] "" XXX + SG_ SET_ME_X02 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XFF2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 7|4@0+ (1,0) [0|255] "" XXX + +BO_ 14 STEER_TORQUE: 8 XXX + SG_ STEER_TORQUE : 15|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 888 CRUISE_CONTROL3: 8 XXX + SG_ NEW_SIGNAL_2 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 38|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_5 : 32|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_DISABLED : 36|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ENABLED : 34|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X003 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X004 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X002 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ CRUISE_SET_SPEED : 15|8@0+ (1,0) [0|63] "mph" XXX + SG_ CRUISE_SPEED_CHANGE : 55|1@0+ (1,0) [0|1] "" XXX + +BO_ 307 POWER_SEATS: 8 XXX + SG_ DRIVER_FORWARD : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVER_BACK : 1|1@0+ (1,0) [0|1] "" XXX + +BO_ 109 GEAR_LEVER: 8 XXX + SG_ PARK_BUTTON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ NEUTRAL_UP : 9|1@0+ (1,0) [0|1] "" XXX + SG_ NEUTRAL_DOWN : 10|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE : 11|1@0+ (1,0) [0|1] "" XXX + SG_ REVERSE : 8|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 23|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 115 GEAR_PACKET: 8 XXX + SG_ GEAR : 0|4@1+ (1,0) [0|15] "" XXX + +BO_ 581 IGNITION: 8 XXX + +BO_ 515 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_MOVING_FR : 22|1@1+ (1,0) [0|15] "" XXX + SG_ WHEEL_MOVING_RL : 38|1@0+ (1,0) [0|1] "" XXX + SG_ WHEEL_MOVING_FL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ WHEEL_MOVING_RR : 54|1@0+ (1,0) [0|1] "" XXX + SG_ WHEEL_SPEED_FL : 2|11@0+ (0.0375,0) [0|255] "mph" XXX + SG_ WHEEL_SPEED_FR : 18|11@0+ (0.0375,0) [0|255] "mph" XXX + SG_ WHEEL_SPEED_RL : 34|11@0+ (0.0375,0) [0|255] "mph" XXX + SG_ WHEEL_SPEED_RR : 50|11@0+ (0.0375,0) [0|255] "mph" XXX + + + + +CM_ SG_ 3 STEER_DIRECTION "0 = left, 1 = right"; +CM_ SG_ 5 BRAKE_POSITION "computer and driver"; +CM_ SG_ 5 BRAKE_PRESSED "computer and driver"; +CM_ SG_ 261 GAS_PEDAL "user gas input"; +CM_ SG_ 261 COMBINED_GAS "computer and driver gas"; +CM_ SG_ 257 CRUISE_ACCELERATING ""; \ No newline at end of file diff --git a/opendbc/tesla_can.dbc b/opendbc/tesla_can.dbc index 5858d1750efa81..37d839e44671c3 100644 --- a/opendbc/tesla_can.dbc +++ b/opendbc/tesla_can.dbc @@ -328,7 +328,8 @@ 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_ 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" ; diff --git a/opendbc/toyota_avalon_2017_pt_generated.dbc b/opendbc/toyota_avalon_2017_pt_generated.dbc new file mode 100644 index 00000000000000..c44f2e4b1cab3a --- /dev/null +++ b/opendbc/toyota_avalon_2017_pt_generated.dbc @@ -0,0 +1,323 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_avalon_2017_pt.dbc starts here" + + + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|65535] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|3] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc new file mode 100644 index 00000000000000..4a3c48f96cfb81 --- /dev/null +++ b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc @@ -0,0 +1,326 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_camry_hybrid_2018_pt.dbc starts here" + + + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_chr_2018_pt_generated.dbc b/opendbc/toyota_chr_2018_pt_generated.dbc new file mode 100644 index 00000000000000..f9da41c3c2d4a1 --- /dev/null +++ b/opendbc/toyota_chr_2018_pt_generated.dbc @@ -0,0 +1,323 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_chr_2018_pt.dbc starts here" + + + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc b/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc new file mode 100644 index 00000000000000..5c9fdb457ae721 --- /dev/null +++ b/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc @@ -0,0 +1,326 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_chr_hybrid_2018_pt.dbc starts here" + + + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc new file mode 100644 index 00000000000000..0331f23c6c1416 --- /dev/null +++ b/opendbc/toyota_corolla_2017_pt_generated.dbc @@ -0,0 +1,322 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_corolla_2017_pt.dbc starts here" + + + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1.0,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_highlander_2017_pt_generated.dbc b/opendbc/toyota_highlander_2017_pt_generated.dbc new file mode 100644 index 00000000000000..10220a752ddeb0 --- /dev/null +++ b/opendbc/toyota_highlander_2017_pt_generated.dbc @@ -0,0 +1,323 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_highlander_2017_pt.dbc starts here" + + + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|65535] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|3] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc new file mode 100644 index 00000000000000..f69d6629cf3146 --- /dev/null +++ b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc @@ -0,0 +1,323 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_highlander_hybrid_2018_pt.dbc starts here" + + + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 5 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/opendbc/toyota_prius_2017_pt.dbc b/opendbc/toyota_prius_2010_pt.dbc similarity index 80% rename from opendbc/toyota_prius_2017_pt.dbc rename to opendbc/toyota_prius_2010_pt.dbc index 96c1a8f7555991..5dba519583c5bb 100644 --- a/opendbc/toyota_prius_2017_pt.dbc +++ b/opendbc/toyota_prius_2010_pt.dbc @@ -35,25 +35,26 @@ BS_: BU_: XXX DSU HCU EPS IPAS + BO_ 36 KINEMATICS: 8 XXX SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX - SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX BO_ 166 BRAKE: 8 XXX SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.0062,-67.67) [0|250] "mph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.0062,-67.67) [0|250] "mph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.0062,-67.67) [0|250] "mph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.0062,-67.67) [0|250] "mph" XXX BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + SG_ SPEED : 47|16@0+ (0.0062,0) [0|115] "mph" XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX BO_ 295 GEAR_PACKET: 8 XXX SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX @@ -63,7 +64,6 @@ BO_ 295 GEAR_PACKET: 8 XXX BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX @@ -77,8 +77,8 @@ BO_ 552 ACCELEROMETER: 8 XXX SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX +BO_ 560 BRAKE_MODULE2: 8 XXX + SG_ BRAKE_LIGHTS : 26|1@0+ (1,0) [0|1] "" XXX BO_ 581 GAS_PEDAL: 8 XXX SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX @@ -89,18 +89,17 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 XXX SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 610 EPS_STATUS: 8 EPS +BO_ 610 EPS_STATUS: 5 EPS SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 643 PRE_COLLISION: 8 XXX @@ -142,10 +141,6 @@ BO_ 921 PCM_CRUISE_SM: 8 XXX BO_ 951 ESP_CONTROL: 8 ESP SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX BO_ 1042 LKAS_HUD: 8 XXX SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX @@ -156,7 +151,6 @@ BO_ 1042 LKAS_HUD: 8 XXX SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX BO_ 1553 UI_SEETING: 8 XXX SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX @@ -168,39 +162,42 @@ BO_ 1568 SEATS_DOORS: 8 XXX SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX +BO_ 452 POWERTRAIN: 8 XXX + SG_ ENGINE_RPM : 7|16@0+ (1,0) [0|65535] "rpm" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + + + CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 560 BRAKE_LIGHTS "double check"; CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, nut it's always 1 in drive traces"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B" ; VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; -VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 50 "temporary_fault"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled" ; +VAL_ 610 LKA_STATE 50 "temporary_fault" ; +VAL_ 614 STATE 3 "enabled" 1 "disabled" ; +VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left" ; VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ; -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"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; - +VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted" ; +VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none" ; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none" ; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none" ; +VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none" ; +VAL_ 1553 UNITS 1 "km" 2 "miles" ; CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; diff --git a/opendbc/toyota_prius_2017_adas.dbc b/opendbc/toyota_prius_2017_adas.dbc index 9d1646f04af4dc..4aae65aa408baa 100644 --- a/opendbc/toyota_prius_2017_adas.dbc +++ b/opendbc/toyota_prius_2017_adas.dbc @@ -182,80 +182,95 @@ BO_ 543 TRACK_A_15: 8 XXX BO_ 544 TRACK_B_0: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 545 TRACK_B_1: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 546 TRACK_B_2: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 547 TRACK_B_3: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 548 TRACK_B_4: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 549 TRACK_B_5: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 550 TRACK_B_6: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 551 TRACK_B_7: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 552 TRACK_B_8: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 553 TRACK_B_9: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 554 TRACK_B_10: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 555 TRACK_B_11: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 556 TRACK_B_12: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 557 TRACK_B_13: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 558 TRACK_B_14: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 559 TRACK_B_15: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX - diff --git a/opendbc/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc new file mode 100644 index 00000000000000..73de10d50a6285 --- /dev/null +++ b/opendbc/toyota_prius_2017_pt_generated.dbc @@ -0,0 +1,330 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_prius_2017_pt.dbc starts here" + + + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1083 AUTOPARK_STATUS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 1083 STATE "when the dashboard button is pressed, the value changes from zero to non-zero"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc new file mode 100644 index 00000000000000..a63c5351f63fb6 --- /dev/null +++ b/opendbc/toyota_rav4_2017_pt_generated.dbc @@ -0,0 +1,322 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_rav4_2017_pt.dbc starts here" + + + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc new file mode 100644 index 00000000000000..2d3825d03ddfc9 --- /dev/null +++ b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc @@ -0,0 +1,323 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _toyota_2017.dbc starts here" +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_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" 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 + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off"; +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_ 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"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_rav4_hybrid_2017_pt.dbc starts here" + + + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 5 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/panda/.circleci/config.yml b/panda/.circleci/config.yml new file mode 100644 index 00000000000000..2c7805a5bb6c78 --- /dev/null +++ b/panda/.circleci/config.yml @@ -0,0 +1,49 @@ +version: 2 +jobs: + safety: + machine: + docker_layer_caching: true + steps: + - checkout + - run: + name: Build image + command: "docker build -t panda_safety -f tests/safety/Dockerfile ." + - run: + name: Run safety test + command: | + docker run panda_safety /bin/bash -c "cd /panda/tests/safety; ./test.sh" + build: + machine: + docker_layer_caching: true + steps: + - checkout + - run: + name: Build image + command: "docker build -t panda_build -f tests/build/Dockerfile ." + - run: + name: Test python package installer + command: | + docker run panda_build /bin/bash -c "cd /panda; python setup.py install" + - run: + name: Build Panda STM image + command: | + docker run panda_build /bin/bash -c "cd /panda/board; make bin" + - run: + name: Build Pedal STM image + command: | + docker run panda_build /bin/bash -c "cd /panda/board/pedal; make obj/comma.bin" + - run: + name: Build NEO STM image + command: | + docker run panda_build /bin/bash -c "cd /panda/board; make clean; make -f Makefile.legacy obj/comma.bin" + - run: + name: Build ESP image + command: | + docker run panda_build /bin/bash -c "cd /panda/boardesp; make user1.bin" + +workflows: + version: 2 + main: + jobs: + - safety + - build diff --git a/panda/.gitignore b/panda/.gitignore index c589cb1c808100..7b7762ef490663 100644 --- a/panda/.gitignore +++ b/panda/.gitignore @@ -2,6 +2,8 @@ .*.swp .*.swo *.o +*.so +*.d a.out *~ .#* diff --git a/panda/.travis.yml b/panda/.travis.yml deleted file mode 100644 index 603848fd2434c3..00000000000000 --- a/panda/.travis.yml +++ /dev/null @@ -1,20 +0,0 @@ -language: python - -cache: - directories: - - build/commaai/panda/boardesp/esp-open-sdk/crosstool-NG - -addons: - apt: - packages: - - gcc-arm-none-eabi - - libnewlib-arm-none-eabi - - gperf - - texinfo - - help2man - -script: - - python setup.py install - - pushd board && make bin && popd - - pushd boardesp && git clone --recursive https://github.com/pfalcon/esp-open-sdk.git && pushd esp-open-sdk && git checkout 03f5e898a059451ec5f3de30e7feff30455f7cec && LD_LIBRARY_PATH="" make STANDALONE=y && popd && popd - - pushd boardesp && make user1.bin && popd diff --git a/panda/README.md b/panda/README.md index 75424f9ce64a38..e323d400e1fdec 100644 --- a/panda/README.md +++ b/panda/README.md @@ -3,7 +3,7 @@ Welcome to panda [panda](http://github.com/commaai/panda) is the nicest universal car interface ever. - + @@ -13,9 +13,9 @@ It uses an [STM32F413](http://www.st.com/en/microcontrollers/stm32f413-423.html? It is 2nd gen hardware, reusing code and parts from the [NEO](https://github.com/commaai/neo) interface board. -[![Build Status](https://travis-ci.org/commaai/panda.svg?branch=master)](https://travis-ci.org/commaai/panda) +[![CircleCI](https://circleci.com/gh/commaai/panda.svg?style=svg)](https://circleci.com/gh/commaai/panda) -Usage +Usage (Python) ------ To install the library: @@ -35,17 +35,23 @@ And to send one on bus 0: ``` >>> panda.can_send(0x1aa, "message", 0) ``` -More examples coming soon +Find user made scripts on the [wiki](https://community.comma.ai/wiki/index.php/Panda_scripts) + +Usage (JavaScript) +------- + +See [PandaJS](https://github.com/commaai/pandajs) + Software interface support ------ As a universal car interface, it should support every reasonable software interface. -- User space ([done](https://github.com/commaai/panda/tree/master/python)) -- socketcan in kernel ([alpha](https://github.com/commaai/panda/tree/master/drivers/linux)) -- ELM327 ([done](https://github.com/commaai/panda/blob/master/boardesp/elm327.c)) -- Windows J2534 ([alpha](https://github.com/commaai/panda/tree/master/drivers/windows)) +- [User space](https://github.com/commaai/panda/tree/master/python) +- [socketcan in kernel](https://github.com/commaai/panda/tree/master/drivers/linux) (alpha) +- [ELM327](https://github.com/commaai/panda/blob/master/boardesp/elm327.c) +- [Windows J2534](https://github.com/commaai/panda/tree/master/drivers/windows) Directory structure ------ diff --git a/panda/VERSION b/panda/VERSION index 13637f44aed339..301779b03ec401 100644 --- a/panda/VERSION +++ b/panda/VERSION @@ -1 +1 @@ -v1.0.3 \ No newline at end of file +v1.1.7 \ No newline at end of file diff --git a/panda/__init__.py b/panda/__init__.py index 912b4427cc854c..b802cf5a59582a 100644 --- a/panda/__init__.py +++ b/panda/__init__.py @@ -1 +1 @@ -from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st +from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial diff --git a/panda/board/Makefile b/panda/board/Makefile index af274d2b27e428..ed6dcaa0309fc8 100644 --- a/panda/board/Makefile +++ b/panda/board/Makefile @@ -2,7 +2,7 @@ PROJ_NAME = panda CFLAGS = -g -Wall CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m4 -CFLAGS += -mhard-float -DSTM32F4 -DSTM32F413xx +CFLAGS += -mhard-float -DSTM32F4 -DSTM32F413xx -mfpu=fpv4-sp-d16 -fsingle-precision-constant STARTUP_FILE = startup_stm32f413xx include build.mk diff --git a/panda/board/bootstub.c b/panda/board/bootstub.c index 147d75a010ab7f..4e516110c5d4bb 100644 --- a/panda/board/bootstub.c +++ b/panda/board/bootstub.c @@ -24,6 +24,12 @@ #include "drivers/usb.h" //#include "drivers/uart.h" +#ifdef PEDAL +#define CUSTOM_CAN_INTERRUPTS +#include "safety.h" +#include "drivers/can.h" +#endif + int puts(const char *a) { return 0; } void puth(unsigned int i) {} diff --git a/panda/board/build.mk b/panda/board/build.mk index 7b3e271915ec12..aee724c19044c1 100644 --- a/panda/board/build.mk +++ b/panda/board/build.mk @@ -1,4 +1,5 @@ -CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -O0 +CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -O2 + CFLAGS += -Tstm32_flash.ld CC = arm-none-eabi-gcc @@ -17,7 +18,7 @@ DFU_UTIL = "dfu-util" # this no longer pushes the bootstub flash: obj/$(PROJ_NAME).bin - PYTHONPATH=../ python -c "from panda import Panda; Panda().flash('obj/$(PROJ_NAME).bin')" + PYTHONPATH=../ python -c "from python import Panda; Panda().flash('obj/$(PROJ_NAME).bin')" ota: obj/$(PROJ_NAME).bin curl http://192.168.0.10/stupdate --upload-file $< @@ -26,7 +27,7 @@ bin: obj/$(PROJ_NAME).bin # this flashes everything recover: obj/bootstub.$(PROJ_NAME).bin obj/$(PROJ_NAME).bin - -PYTHONPATH=../ python -c "from panda import Panda; Panda().reset(enter_bootloader=True)" + -PYTHONPATH=../ python -c "from python import Panda; Panda().reset(enter_bootloader=True)" sleep 1.0 $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.$(PROJ_NAME).bin diff --git a/panda/board/drivers/can.h b/panda/board/drivers/can.h index 422da965cfeba4..b837094c9a0d38 100644 --- a/panda/board/drivers/can.h +++ b/panda/board/drivers/can.h @@ -86,6 +86,7 @@ int can_err_cnt = 0; uint8_t can_num_lookup[] = {0,1,2,-1}; int8_t can_forwarding[] = {-1,-1,-1,-1}; uint32_t can_speed[] = {5000, 5000, 5000, 333}; + bool can_autobaud_enabled[] = {false, false, false, false}; #define CAN_MAX 3 #else CAN_TypeDef *cans[] = {CAN1, CAN2}; @@ -93,10 +94,21 @@ int can_err_cnt = 0; uint8_t can_num_lookup[] = {1,0}; int8_t can_forwarding[] = {-1,-1}; uint32_t can_speed[] = {5000, 5000}; + bool can_autobaud_enabled[] = {false, false}; #define CAN_MAX 2 #endif +uint32_t can_autobaud_speeds[] = {5000, 2500, 1250, 1000, 10000}; +#define AUTOBAUD_SPEEDS_LEN (sizeof(can_autobaud_speeds) / sizeof(can_autobaud_speeds[0])) + #define CANIF_FROM_CAN_NUM(num) (cans[num]) +#ifdef PANDA +#define CAN_NUM_FROM_CANIF(CAN) (CAN==CAN1 ? 0 : (CAN==CAN2 ? 1 : 2)) +#define CAN_NAME_FROM_CANIF(CAN) (CAN==CAN1 ? "CAN1" : (CAN==CAN2 ? "CAN2" : "CAN3")) +#else +#define CAN_NUM_FROM_CANIF(CAN) (CAN==CAN1 ? 0 : 1) +#define CAN_NAME_FROM_CANIF(CAN) (CAN==CAN1 ? "CAN1" : "CAN2") +#endif #define BUS_NUM_FROM_CAN_NUM(num) (bus_lookup[num]) #define CAN_NUM_FROM_BUS_NUM(num) (can_num_lookup[num]) @@ -115,43 +127,78 @@ int can_err_cnt = 0; // 5000 = 500 kbps #define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10 / (x)) -void process_can(uint8_t can_number); +void can_autobaud_speed_increment(uint8_t can_number) { + uint32_t autobaud_speed = can_autobaud_speeds[0]; + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + for (int i = 0; i < AUTOBAUD_SPEEDS_LEN; i++) { + if (can_speed[bus_number] == can_autobaud_speeds[i]) { + if (i+1 < AUTOBAUD_SPEEDS_LEN) { + autobaud_speed = can_autobaud_speeds[i+1]; + } + break; + } + } + can_speed[bus_number] = autobaud_speed; +#ifdef DEBUG + CAN_TypeDef* CAN = CANIF_FROM_CAN_NUM(can_number); + puts(CAN_NAME_FROM_CANIF(CAN)); + puts(" auto-baud test "); + putui(can_speed[bus_number]); + puts(" cbps\n"); +#endif +} -void can_init(uint8_t can_number) { - if (can_number == 0xff) return; +void process_can(uint8_t can_number); +void can_set_speed(uint8_t can_number) { CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); - set_can_enable(CAN, 1); - - CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ; - while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); - // set time quanta from defines - CAN->BTR = (CAN_BTR_TS1_0 * (CAN_SEQ1-1)) | - (CAN_BTR_TS2_0 * (CAN_SEQ2-1)) | - (can_speed_to_prescaler(can_speed[BUS_NUM_FROM_CAN_NUM(can_number)]) - 1); + while (true) { + // initialization mode + CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ; + while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK); - // silent loopback mode for debugging - if (can_loopback) { - CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM; - } + // set time quanta from defines + CAN->BTR = (CAN_BTR_TS1_0 * (CAN_SEQ1-1)) | + (CAN_BTR_TS2_0 * (CAN_SEQ2-1)) | + (can_speed_to_prescaler(can_speed[bus_number]) - 1); - if (can_silent & (1 << can_number)) { - CAN->BTR |= CAN_BTR_SILM; - } + // silent loopback mode for debugging + if (can_loopback) { + CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM; + } + if (can_silent & (1 << can_number)) { + CAN->BTR |= CAN_BTR_SILM; + } - // reset - CAN->MCR = CAN_MCR_TTCM | CAN_MCR_ABOM; + // reset + CAN->MCR = CAN_MCR_TTCM | CAN_MCR_ABOM; - #define CAN_TIMEOUT 1000000 - int tmp = 0; - while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK && tmp < CAN_TIMEOUT) tmp++; + #define CAN_TIMEOUT 1000000 + int tmp = 0; + while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK && tmp < CAN_TIMEOUT) tmp++; + if (tmp < CAN_TIMEOUT) { + return; + } - if (tmp == CAN_TIMEOUT) { - puts("CAN init FAILED!!!!!\n"); - puth(can_number); puts(" "); - puth(BUS_NUM_FROM_CAN_NUM(can_number)); puts("\n"); + if (can_autobaud_enabled[bus_number]) { + can_autobaud_speed_increment(can_number); + } else { + puts("CAN init FAILED!!!!!\n"); + puth(can_number); puts(" "); + puth(BUS_NUM_FROM_CAN_NUM(can_number)); puts("\n"); + return; + } } +} + +void can_init(uint8_t can_number) { + if (can_number == 0xff) return; + + CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); + set_can_enable(CAN, 1); + can_set_speed(can_number); // accept all filter CAN->FMR |= CAN_FMR_FINIT; @@ -166,7 +213,7 @@ void can_init(uint8_t can_number) { CAN->FMR &= ~(CAN_FMR_FINIT); // enable certain CAN interrupts - CAN->IER = CAN_IER_TMEIE | CAN_IER_FMPIE0; + CAN->IER |= CAN_IER_TMEIE | CAN_IER_FMPIE0; switch (can_number) { case 0: @@ -199,6 +246,7 @@ void can_init_all() { } void can_set_gmlan(int bus) { + #ifdef PANDA if (bus == -1 || bus != can_num_lookup[3]) { // GMLAN OFF switch (can_num_lookup[3]) { @@ -238,10 +286,13 @@ void can_set_gmlan(int bus) { can_num_lookup[3] = 2; can_init(2); } + #endif } // CAN error void can_sce(CAN_TypeDef *CAN) { + enter_critical_section(); + can_err_cnt += 1; #ifdef DEBUG if (CAN==CAN1) puts("CAN1: "); @@ -262,9 +313,19 @@ void can_sce(CAN_TypeDef *CAN) { puts("\n"); #endif + uint8_t can_number = CAN_NUM_FROM_CANIF(CAN); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + if (can_autobaud_enabled[bus_number] && (CAN->ESR & CAN_ESR_LEC)) { + can_autobaud_speed_increment(can_number); + can_set_speed(can_number); + } + // clear current send CAN->TSR |= CAN_TSR_ABRQ0; + CAN->MSR &= ~(CAN_MSR_ERRI); CAN->MSR = CAN->MSR; + + exit_critical_section(); } // ***************************** CAN ***************************** @@ -332,6 +393,16 @@ void can_rx(uint8_t can_number) { CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); while (CAN->RF0R & CAN_RF0R_FMP0) { + if (can_autobaud_enabled[bus_number]) { + can_autobaud_enabled[bus_number] = false; + puts(CAN_NAME_FROM_CANIF(CAN)); + #ifdef DEBUG + puts(" auto-baud "); + putui(can_speed[bus_number]); + puts(" cbps\n"); + #endif + } + can_rx_cnt += 1; // can is live @@ -344,20 +415,22 @@ void can_rx(uint8_t can_number) { to_push.RDLR = CAN->sFIFOMailBox[0].RDLR; to_push.RDHR = CAN->sFIFOMailBox[0].RDHR; + // modify RDTR for our API + to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (bus_number << 4); + // forwarding (panda only) #ifdef PANDA - if (can_forwarding[bus_number] != -1) { + int bus_fwd_num = can_forwarding[bus_number] != -1 ? can_forwarding[bus_number] : safety_fwd_hook(bus_number, &to_push); + if (bus_fwd_num != -1) { CAN_FIFOMailBox_TypeDef to_send; to_send.RIR = to_push.RIR | 1; // TXRQ to_send.RDTR = to_push.RDTR; to_send.RDLR = to_push.RDLR; to_send.RDHR = to_push.RDHR; - can_send(&to_send, can_forwarding[bus_number]); + can_send(&to_send, bus_fwd_num); } #endif - // modify RDTR for our API - to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (bus_number << 4); safety_rx_hook(&to_push); #ifdef PANDA @@ -370,6 +443,8 @@ void can_rx(uint8_t can_number) { } } +#ifndef CUSTOM_CAN_INTERRUPTS + void CAN1_TX_IRQHandler() { process_can(0); } void CAN1_RX0_IRQHandler() { can_rx(0); } void CAN1_SCE_IRQHandler() { can_sce(CAN1); } @@ -384,14 +459,23 @@ void CAN3_RX0_IRQHandler() { can_rx(2); } void CAN3_SCE_IRQHandler() { can_sce(CAN3); } #endif +#endif + void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number) { - if (safety_tx_hook(to_push)) { + if (safety_tx_hook(to_push) && !can_autobaud_enabled[bus_number]) { if (bus_number < BUS_MAX) { // add CAN packet to send queue // bus number isn't passed through to_push->RDTR &= 0xF; - can_push(can_queues[bus_number], to_push); - process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); + if (bus_number == 3 && can_num_lookup[3] == 0xFF) { + #ifdef PANDA + // TODO: why uint8 bro? only int8? + bitbang_gmlan(to_push); + #endif + } else { + can_push(can_queues[bus_number], to_push); + process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); + } } } } diff --git a/panda/board/drivers/drivers.h b/panda/board/drivers/drivers.h index 871ee8fcf1f88a..d3409d60994eed 100644 --- a/panda/board/drivers/drivers.h +++ b/panda/board/drivers/drivers.h @@ -57,13 +57,13 @@ void usb_cb_enumeration_complete(); // ********************* UART ********************* // IRQs: USART1, USART2, USART3, UART5 -#define FIFO_SIZE 0x100 +#define FIFO_SIZE 0x400 typedef struct uart_ring { - uint8_t w_ptr_tx; - uint8_t r_ptr_tx; + uint16_t w_ptr_tx; + uint16_t r_ptr_tx; uint8_t elems_tx[FIFO_SIZE]; - uint8_t w_ptr_rx; - uint8_t r_ptr_rx; + uint16_t w_ptr_rx; + uint16_t r_ptr_rx; uint8_t elems_rx[FIFO_SIZE]; USART_TypeDef *uart; void (*callback)(struct uart_ring*); @@ -88,7 +88,7 @@ uint32_t adc_get(int channel); // ********************* DAC ********************* void dac_init(); -uint32_t dac_set(int channel, uint32_t value); +void dac_set(int channel, uint32_t value); // ********************* TIMER ********************* diff --git a/panda/board/drivers/gmlan_alt.h b/panda/board/drivers/gmlan_alt.h new file mode 100644 index 00000000000000..8521100a88083a --- /dev/null +++ b/panda/board/drivers/gmlan_alt.h @@ -0,0 +1,276 @@ +#define GMLAN_TICKS_PER_SECOND 33300 //1sec @ 33.3kbps +#define GMLAN_TICKS_PER_TIMEOUT_TICKLE 500 //15ms @ 33.3kbps +#define GMLAN_HIGH 0 //0 is high on bus (dominant) +#define GMLAN_LOW 1 //1 is low on bus + +#define DISABLED -1 +#define BITBANG 0 +#define GPIO_SWITCH 1 + +#define MAX_BITS_CAN_PACKET (200) + +int gmlan_alt_mode = DISABLED; + +// returns out_len +int do_bitstuff(char *out, char *in, int in_len) { + int last_bit = -1; + int bit_cnt = 0; + int j = 0; + for (int i = 0; i < in_len; i++) { + char bit = in[i]; + out[j++] = bit; + + // do the stuffing + if (bit == last_bit) { + bit_cnt++; + if (bit_cnt == 5) { + // 5 in a row the same, do stuff + last_bit = !bit; + out[j++] = last_bit; + bit_cnt = 1; + } + } else { + // this is a new bit + last_bit = bit; + bit_cnt = 1; + } + } + return j; +} + +int append_crc(char *in, int in_len) { + int crc = 0; + for (int i = 0; i < in_len; i++) { + crc <<= 1; + if (in[i] ^ ((crc>>15)&1)) { + crc = crc ^ 0x4599; + } + crc &= 0x7fff; + } + for (int i = 14; i >= 0; i--) { + in[in_len++] = (crc>>i)&1; + } + return in_len; +} + +int append_bits(char *in, int in_len, char *app, int app_len) { + for (int i = 0; i < app_len; i++) { + in[in_len++] = app[i]; + } + return in_len; +} + +int append_int(char *in, int in_len, int val, int val_len) { + for (int i = val_len-1; i >= 0; i--) { + in[in_len++] = (val&(1<RDTR & 0xF; + len = append_int(pkt, len, 0, 1); // Start-of-frame + + if (to_bang->RIR & 4) { + // extended identifier + len = append_int(pkt, len, to_bang->RIR >> 21, 11); // Identifier + len = append_int(pkt, len, 3, 2); // SRR+IDE + len = append_int(pkt, len, (to_bang->RIR >> 3) & ((1<<18)-1), 18); // Identifier + len = append_int(pkt, len, 0, 3); // RTR+r1+r0 + } else { + // standard identifier + len = append_int(pkt, len, to_bang->RIR >> 21, 11); // Identifier + len = append_int(pkt, len, 0, 3); // RTR+IDE+reserved + } + + len = append_int(pkt, len, dlc_len, 4); // Data length code + + // append data + for (int i = 0; i < dlc_len; i++) { + unsigned char dat = ((unsigned char *)(&(to_bang->RDLR)))[i]; + len = append_int(pkt, len, dat, 8); + } + + // append crc + len = append_crc(pkt, len); + + // do bitstuffing + len = do_bitstuff(out, pkt, len); + + // append footer + len = append_bits(out, len, footer, sizeof(footer)); + return len; +} + +#ifdef PANDA + +void setup_timer4() { + // setup + TIM4->PSC = 48-1; // tick on 1 us + TIM4->CR1 = TIM_CR1_CEN; // enable + TIM4->ARR = 30-1; // 33.3 kbps + + // in case it's disabled + NVIC_EnableIRQ(TIM4_IRQn); + + // run the interrupt + TIM4->DIER = TIM_DIER_UIE; // update interrupt + TIM4->SR = 0; +} + +int gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; //GMLAN transceiver times out every 17ms held high; tickle every 15ms +int can_timeout_counter = GMLAN_TICKS_PER_SECOND; //1 second + +int inverted_bit_to_send = GMLAN_HIGH; +int gmlan_switch_below_timeout = -1; +int gmlan_switch_timeout_enable = 0; + +void gmlan_switch_init(int timeout_enable) { + gmlan_switch_timeout_enable = timeout_enable; + gmlan_alt_mode = GPIO_SWITCH; + gmlan_switch_below_timeout = 1; + set_gpio_mode(GPIOB, 13, MODE_OUTPUT); + + setup_timer4(); + + inverted_bit_to_send = GMLAN_LOW; //We got initialized, set the output low +} + +void set_gmlan_digital_output(int to_set) { + inverted_bit_to_send = to_set; + /* + puts("Writing "); + puth(inverted_bit_to_send); + puts("\n"); + */ +} + +void reset_gmlan_switch_timeout(void) { + can_timeout_counter = GMLAN_TICKS_PER_SECOND; + gmlan_switch_below_timeout = 1; + gmlan_alt_mode = GPIO_SWITCH; +} + +void set_bitbanged_gmlan(int val) { + if (val) { + GPIOB->ODR |= (1 << 13); + } else { + GPIOB->ODR &= ~(1 << 13); + } +} + +char pkt_stuffed[MAX_BITS_CAN_PACKET]; +int gmlan_sending = -1; +int gmlan_sendmax = -1; + +int gmlan_silent_count = 0; +int gmlan_fail_count = 0; +#define REQUIRED_SILENT_TIME 10 +#define MAX_FAIL_COUNT 10 + +void TIM4_IRQHandler(void) { + if (gmlan_alt_mode == BITBANG) { + if (TIM4->SR & TIM_SR_UIF && gmlan_sendmax != -1) { + int read = get_gpio_input(GPIOB, 12); + if (gmlan_silent_count < REQUIRED_SILENT_TIME) { + if (read == 0) { + gmlan_silent_count = 0; + } else { + gmlan_silent_count++; + } + } else if (gmlan_silent_count == REQUIRED_SILENT_TIME) { + int retry = 0; + // in send loop + if (gmlan_sending > 0 && // not first bit + (read == 0 && pkt_stuffed[gmlan_sending-1] == 1) && // bus wrongly dominant + gmlan_sending != (gmlan_sendmax-11)) { //not ack bit + puts("GMLAN ERR: bus driven at "); + puth(gmlan_sending); + puts("\n"); + retry = 1; + } else if (read == 1 && gmlan_sending == (gmlan_sendmax-11)) { // recessive during ACK + puts("GMLAN ERR: didn't recv ACK\n"); + retry = 1; + } + if (retry) { + // reset sender (retry after 7 silent) + set_bitbanged_gmlan(1); // recessive + gmlan_silent_count = 0; + gmlan_sending = 0; + gmlan_fail_count++; + if (gmlan_fail_count == MAX_FAIL_COUNT) { + puts("GMLAN ERR: giving up send\n"); + } + } else { + set_bitbanged_gmlan(pkt_stuffed[gmlan_sending]); + gmlan_sending++; + } + } + if (gmlan_sending == gmlan_sendmax || gmlan_fail_count == MAX_FAIL_COUNT) { + set_bitbanged_gmlan(1); // recessive + set_gpio_mode(GPIOB, 13, MODE_INPUT); + TIM4->DIER = 0; // no update interrupt + TIM4->CR1 = 0; // disable timer + gmlan_sendmax = -1; // exit + } + } + TIM4->SR = 0; + } //bit bang mode + + else if (gmlan_alt_mode == GPIO_SWITCH) { + if (TIM4->SR & TIM_SR_UIF && gmlan_switch_below_timeout != -1) { + if (can_timeout_counter == 0 && gmlan_switch_timeout_enable) { + //it has been more than 1 second since timeout was reset; disable timer and restore the GMLAN output + set_gpio_output(GPIOB, 13, GMLAN_LOW); + gmlan_switch_below_timeout = -1; + gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; + gmlan_alt_mode = DISABLED; + } + else { + can_timeout_counter--; + if (gmlan_timeout_counter == 0) { + //Send a 1 (bus low) every 15ms to reset the GMLAN transceivers timeout + gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; + set_gpio_output(GPIOB, 13, GMLAN_LOW); + } + else { + set_gpio_output(GPIOB, 13, inverted_bit_to_send); + gmlan_timeout_counter--; + } + } + } + TIM4->SR = 0; + } //gmlan switch mode +} + +void bitbang_gmlan(CAN_FIFOMailBox_TypeDef *to_bang) { + gmlan_alt_mode = BITBANG; + // TODO: make failure less silent + if (gmlan_sendmax != -1) return; + + int len = get_bit_message(pkt_stuffed, to_bang); + gmlan_fail_count = 0; + gmlan_silent_count = 0; + gmlan_sending = 0; + gmlan_sendmax = len; + + // setup for bitbang loop + set_bitbanged_gmlan(1); // recessive + set_gpio_mode(GPIOB, 13, MODE_OUTPUT); + + setup_timer4(); +} + +#endif diff --git a/panda/board/drivers/spi.h b/panda/board/drivers/spi.h index fc6a5ab26dca0f..7a5945d37257cb 100644 --- a/panda/board/drivers/spi.h +++ b/panda/board/drivers/spi.h @@ -40,6 +40,7 @@ void spi_tx_dma(void *addr, int len) { // channel3, increment memory, memory -> periph, enable DMA2_Stream3->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_EN; + delay(0); DMA2_Stream3->CR |= DMA_SxCR_TCIE; SPI1->CR2 |= SPI_CR2_TXDMAEN; @@ -65,6 +66,7 @@ void spi_rx_dma(void *addr, int len) { // channel3, increment memory, periph -> memory, enable DMA2_Stream2->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_EN; + delay(0); DMA2_Stream2->CR |= DMA_SxCR_TCIE; SPI1->CR2 |= SPI_CR2_RXDMAEN; @@ -95,7 +97,7 @@ void DMA2_Stream2_IRQHandler(void) { void DMA2_Stream3_IRQHandler(void) { #ifdef DEBUG_SPI puts("SPI handshake\n"); - #endif + #endif // reset handshake back to pull up set_gpio_mode(GPIOB, 0, MODE_INPUT); diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index 85bab0e78d1ab0..5ca82888d4fe7a 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -5,16 +5,19 @@ // esp = USART1 uart_ring esp_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, .w_ptr_rx = 0, .r_ptr_rx = 0, - .uart = USART1 }; + .uart = USART1, + .callback = NULL}; // lin1, K-LINE = UART5 // lin2, L-LINE = USART3 uart_ring lin1_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, .w_ptr_rx = 0, .r_ptr_rx = 0, - .uart = UART5 }; + .uart = UART5, + .callback = NULL}; uart_ring lin2_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, .w_ptr_rx = 0, .r_ptr_rx = 0, - .uart = USART3 }; + .uart = USART3, + .callback = NULL}; // debug = USART2 void debug_ring_callback(uart_ring *ring); @@ -49,7 +52,7 @@ void uart_ring_process(uart_ring *q) { if (q->w_ptr_tx != q->r_ptr_tx) { if (sr & USART_SR_TXE) { q->uart->DR = q->elems_tx[q->r_ptr_tx]; - q->r_ptr_tx += 1; + q->r_ptr_tx = (q->r_ptr_tx + 1) % FIFO_SIZE; } else { // push on interrupt later q->uart->CR1 |= USART_CR1_TXEIE; @@ -59,15 +62,22 @@ void uart_ring_process(uart_ring *q) { q->uart->CR1 &= ~USART_CR1_TXEIE; } - if (sr & USART_SR_RXNE) { + if (sr & USART_SR_RXNE || sr & USART_SR_ORE) { uint8_t c = q->uart->DR; // TODO: can drop packets - uint8_t next_w_ptr = q->w_ptr_rx + 1; - 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) q->callback(q); + if (q != &esp_ring) { + uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; + 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) q->callback(q); + } } } + + if (sr & USART_SR_ORE) { + // set dropped packet flag? + } + exit_critical_section(); } @@ -84,7 +94,7 @@ int getc(uart_ring *q, char *elem) { enter_critical_section(); if (q->w_ptr_rx != q->r_ptr_rx) { *elem = q->elems_rx[q->r_ptr_rx]; - q->r_ptr_rx += 1; + q->r_ptr_rx = (q->r_ptr_rx + 1) % FIFO_SIZE; ret = 1; } exit_critical_section(); @@ -94,10 +104,10 @@ int getc(uart_ring *q, char *elem) { int injectc(uart_ring *q, char elem) { int ret = 0; - uint8_t next_w_ptr; + uint16_t next_w_ptr; enter_critical_section(); - next_w_ptr = q->w_ptr_rx + 1; + next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; if (next_w_ptr != q->r_ptr_rx) { q->elems_rx[q->w_ptr_rx] = elem; q->w_ptr_rx = next_w_ptr; @@ -110,10 +120,10 @@ int injectc(uart_ring *q, char elem) { int putc(uart_ring *q, char elem) { int ret = 0; - uint8_t next_w_ptr; + uint16_t next_w_ptr; enter_critical_section(); - next_w_ptr = q->w_ptr_tx + 1; + next_w_ptr = (q->w_ptr_tx + 1) % FIFO_SIZE; if (next_w_ptr != q->r_ptr_tx) { q->elems_tx[q->w_ptr_tx] = elem; q->w_ptr_tx = next_w_ptr; @@ -151,6 +161,51 @@ void uart_set_baud(USART_TypeDef *u, int baud) { } } +#define USART1_DMA_LEN 0x20 +char usart1_dma[USART1_DMA_LEN]; + +void uart_dma_drain() { + uart_ring *q = &esp_ring; + + enter_critical_section(); + + if (DMA2->HISR & DMA_HISR_TCIF5 || DMA2->HISR & DMA_HISR_HTIF5 || DMA2_Stream5->NDTR != USART1_DMA_LEN) { + // disable DMA + q->uart->CR3 &= ~USART_CR3_DMAR; + DMA2_Stream5->CR &= ~DMA_SxCR_EN; + while (DMA2_Stream5->CR & DMA_SxCR_EN); + + int i; + for (i = 0; i < USART1_DMA_LEN - DMA2_Stream5->NDTR; i++) { + char c = usart1_dma[i]; + uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; + if (next_w_ptr != q->r_ptr_rx) { + q->elems_rx[q->w_ptr_rx] = c; + q->w_ptr_rx = next_w_ptr; + } + } + + // reset DMA len + DMA2_Stream5->NDTR = USART1_DMA_LEN; + + // clear interrupts + DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; + //DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; + + // enable DMA + DMA2_Stream5->CR |= DMA_SxCR_EN; + q->uart->CR3 |= USART_CR3_DMAR; + } + + exit_critical_section(); +} + +void DMA2_Stream5_IRQHandler(void) { + //set_led(LED_BLUE, 1); + uart_dma_drain(); + //set_led(LED_BLUE, 0); +} + void uart_init(USART_TypeDef *u, int baud) { // enable uart and tx+rx mode u->CR1 = USART_CR1_UE; @@ -162,9 +217,23 @@ void uart_init(USART_TypeDef *u, int baud) { // ** UART is ready to work ** // enable interrupts - u->CR1 |= USART_CR1_RXNEIE; + if (u != USART1) { + u->CR1 |= USART_CR1_RXNEIE; + } if (u == USART1) { + // DMA2, stream 2, channel 3 + DMA2_Stream5->M0AR = (uint32_t)usart1_dma; + DMA2_Stream5->NDTR = USART1_DMA_LEN; + DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); + + // channel4, increment memory, periph -> memory, enable + DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_EN; + + // this one uses DMA receiver + u->CR3 = USART_CR3_DMAR; + + NVIC_EnableIRQ(DMA2_Stream5_IRQn); NVIC_EnableIRQ(USART1_IRQn); } else if (u == USART2) { NVIC_EnableIRQ(USART2_IRQn); @@ -197,6 +266,17 @@ int puts(const char *a) { return 0; } +void putui(uint32_t i) { + char str[11]; + uint8_t idx = 10; + str[idx--] = '\0'; + do { + str[idx--] = (i % 10) + 0x30; + i /= 10; + } while (i); + puts(str + idx + 1); +} + void puth(unsigned int i) { int pos; char c[] = "0123456789abcdef"; diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index 14c2ae7cdf9ff8..f2cffa1416e645 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -30,13 +30,35 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; #define USB_REQ_SET_INTERFACE 0x0B #define USB_REQ_SYNCH_FRAME 0x0C -#define USB_DESC_TYPE_DEVICE 1 -#define USB_DESC_TYPE_CONFIGURATION 2 -#define USB_DESC_TYPE_STRING 3 -#define USB_DESC_TYPE_INTERFACE 4 -#define USB_DESC_TYPE_ENDPOINT 5 -#define USB_DESC_TYPE_DEVICE_QUALIFIER 6 -#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 7 +#define USB_DESC_TYPE_DEVICE 0x01 +#define USB_DESC_TYPE_CONFIGURATION 0x02 +#define USB_DESC_TYPE_STRING 0x03 +#define USB_DESC_TYPE_INTERFACE 0x04 +#define USB_DESC_TYPE_ENDPOINT 0x05 +#define USB_DESC_TYPE_DEVICE_QUALIFIER 0x06 +#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 0x07 +#define USB_DESC_TYPE_BINARY_OBJECT_STORE 0x0f + +// offsets for configuration strings +#define STRING_OFFSET_LANGID 0x00 +#define STRING_OFFSET_IMANUFACTURER 0x01 +#define STRING_OFFSET_IPRODUCT 0x02 +#define STRING_OFFSET_ISERIAL 0x03 +#define STRING_OFFSET_ICONFIGURATION 0x04 +#define STRING_OFFSET_IINTERFACE 0x05 + +// WebUSB requests +#define WEBUSB_REQ_GET_URL 0x02 + +// WebUSB types +#define WEBUSB_DESC_TYPE_URL 0x03 +#define WEBUSB_URL_SCHEME_HTTPS 0x01 +#define WEBUSB_URL_SCHEME_HTTP 0x00 + +// WinUSB requests +#define WINUSB_REQ_GET_COMPATID_DESCRIPTOR 0x04 +#define WINUSB_REQ_GET_EXT_PROPS_OS 0x05 +#define WINUSB_REQ_GET_DESCRIPTOR 0x07 #define STS_GOUT_NAK 1 #define STS_DATA_UPDT 2 @@ -50,15 +72,6 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; uint8_t resp[MAX_RESP_LEN]; -// descriptor types -// same as setupdat.h -#define DSCR_DEVICE_TYPE 1 -#define DSCR_CONFIG_TYPE 2 -#define DSCR_STRING_TYPE 3 -#define DSCR_INTERFACE_TYPE 4 -#define DSCR_ENDPOINT_TYPE 5 -#define DSCR_DEVQUAL_TYPE 6 - // for the repeating interfaces #define DSCR_INTERFACE_LEN 9 #define DSCR_ENDPOINT_LEN 7 @@ -71,12 +84,26 @@ uint8_t resp[MAX_RESP_LEN]; #define ENDPOINT_TYPE_BULK 2 #define ENDPOINT_TYPE_INT 3 -//Convert machine byte order to USB byte order +// These are arbitrary values used in bRequest +#define MS_VENDOR_CODE 0x20 +#define WEBUSB_VENDOR_CODE 0x30 + +// BOS constants +#define BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH 0x05 +#define BINARY_OBJECT_STORE_DESCRIPTOR 0x0F +#define WINUSB_PLATFORM_DESCRIPTOR_LENGTH 0x9E + +// Convert machine byte order to USB byte order #define TOUSBORDER(num)\ (num&0xFF), ((num>>8)&0xFF) +// take in string length and return the first 2 bytes of a string descriptor +#define STRING_DESCRIPTOR_HEADER(size)\ + (((size * 2 + 2)&0xFF) | 0x0300) + uint8_t device_desc[] = { - DSCR_DEVICE_LEN, DSCR_DEVICE_TYPE, 0x00, 0x01, //Length, Type, bcdUSB + DSCR_DEVICE_LEN, USB_DESC_TYPE_DEVICE, //Length, Type + 0x10, 0x02, // bcdUSB max version of USB supported (2.1) 0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size TOUSBORDER(USB_VID), // idVendor TOUSBORDER(USB_PID), // idProduct @@ -89,85 +116,257 @@ uint8_t device_desc[] = { 0x03, 0x01 // Serial Number, Num Configurations }; +uint8_t device_qualifier[] = { + 0x0a, USB_DESC_TYPE_DEVICE_QUALIFIER, //Length, Type + 0x10, 0x02, // bcdUSB max version of USB supported (2.1) + 0xFF, 0xFF, 0xFF, 0x40, // bDeviceClass, bDeviceSubClass, bDeviceProtocol, bMaxPacketSize0 + 0x01, 0x00 // bNumConfigurations, bReserved +}; + #define ENDPOINT_RCV 0x80 #define ENDPOINT_SND 0x00 uint8_t configuration_desc[] = { - DSCR_CONFIG_LEN, DSCR_CONFIG_TYPE, // Length, Type, + DSCR_CONFIG_LEN, USB_DESC_TYPE_CONFIGURATION, // Length, Type, TOUSBORDER(0x0045), // Total Len (uint16) - 0x01, 0x01, 0x00, // Num Interface, Config Value, Configuration + 0x01, 0x01, STRING_OFFSET_ICONFIGURATION, // Num Interface, Config Value, Configuration 0xc0, 0x32, // Attributes, Max Power // interface 0 ALT 0 - DSCR_INTERFACE_LEN, DSCR_INTERFACE_TYPE, // Length, Type + DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type 0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol 0x00, // Interface // endpoint 1, read CAN - DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type TOUSBORDER(0x0040), // Max Packet (0x0040) 0x00, // Polling Interval (NA) // endpoint 2, send serial - DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type TOUSBORDER(0x0040), // Max Packet (0x0040) 0x00, // Polling Interval // endpoint 3, send CAN - DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type TOUSBORDER(0x0040), // Max Packet (0x0040) 0x00, // Polling Interval // interface 0 ALT 1 - DSCR_INTERFACE_LEN, DSCR_INTERFACE_TYPE, // Length, Type + DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type 0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol 0x00, // Interface // endpoint 1, read CAN - DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type TOUSBORDER(0x0040), // Max Packet (0x0040) 0x05, // Polling Interval (5 frames) // endpoint 2, send serial - DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type TOUSBORDER(0x0040), // Max Packet (0x0040) 0x00, // Polling Interval // endpoint 3, send CAN - DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type TOUSBORDER(0x0040), // Max Packet (0x0040) 0x00, // Polling Interval }; -uint8_t string_0_desc[] = { - 0x04, DSCR_STRING_TYPE, 0x09, 0x04 +// STRING_DESCRIPTOR_HEADER is for uint16 string descriptors +// it takes in a string length, which is bytes/2 because unicode +uint16_t string_language_desc[] = { + STRING_DESCRIPTOR_HEADER(1), + 0x0409 // american english }; -uint16_t string_1_desc[] = { - 0x0312, +// these strings are all uint16's so that we don't need to spam ,0 after every character +uint16_t string_manufacturer_desc[] = { + STRING_DESCRIPTOR_HEADER(8), 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' }; #ifdef PANDA -uint16_t string_2_desc[] = { - 0x030c, +uint16_t string_product_desc[] = { + STRING_DESCRIPTOR_HEADER(5), 'p', 'a', 'n', 'd', 'a' }; #else -uint16_t string_2_desc[] = { - 0x030c, +uint16_t string_product_desc[] = { + STRING_DESCRIPTOR_HEADER(5), 'N', 'E', 'O', 'v', '1' }; #endif -uint16_t string_3_desc[] = { - 0x030a, +// default serial number when we're not a panda +uint16_t string_serial_desc[] = { + STRING_DESCRIPTOR_HEADER(4), 'n', 'o', 'n', 'e' }; +// a string containing the default configuration index +uint16_t string_configuration_desc[] = { + STRING_DESCRIPTOR_HEADER(2), + '0', '1' // "01" +}; + +#ifdef PANDA +// WCID (auto install WinUSB driver) +// https://github.com/pbatard/libwdi/wiki/WCID-Devices +// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file +// WinUSB 1.0 descriptors, this is mostly used by Windows XP +uint8_t string_238_desc[] = { + 0x12, USB_DESC_TYPE_STRING, // bLength, bDescriptorType + 'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100) + MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad +}; +uint8_t winusb_ext_compatid_os_desc[] = { + 0x28, 0x00, 0x00, 0x00, // dwLength + 0x00, 0x01, // bcdVersion + 0x04, 0x00, // wIndex + 0x01, // bCount + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved + 0x00, // bFirstInterfaceNumber + 0x00, // Reserved + 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved +}; +uint8_t winusb_ext_prop_os_desc[] = { + 0x8e, 0x00, 0x00, 0x00, // dwLength + 0x00, 0x01, // bcdVersion + 0x05, 0x00, // wIndex + 0x01, 0x00, // wCount + // first property + 0x84, 0x00, 0x00, 0x00, // dwSize + 0x01, 0x00, 0x00, 0x00, // dwPropertyDataType + 0x28, 0x00, // wPropertyNameLength + 'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID) + 0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength + '{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9}) +}; + +/* +Binary Object Store descriptor used to expose WebUSB (and more WinUSB) metadata +comments are from the wicg spec +References used: + https://wicg.github.io/webusb/#webusb-platform-capability-descriptor + https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c + https://os.mbed.com/users/larsgk/code/USBDevice_WebUSB/file/1d8a6665d607/WebUSBDevice/ + +*/ +uint8_t binary_object_store_desc[] = { + // BOS header + BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH, // bLength, this is only the length of the header + BINARY_OBJECT_STORE_DESCRIPTOR, // bDescriptorType + 0x40, 0x00, // wTotalLength (LSB, MSB) + 0x03, // bNumDeviceCaps (USB 2.0 + WebUSB + WinUSB) + + // ------------------------------------------------- + // USB 2.0 extension descriptor + 0x07, // bLength, Descriptor size + 0x10, // bDescriptorType, Device Capability Descriptor Type + 0x02, // bDevCapabilityType, USB 2.0 extension capability type + 0x00, 0x00, 0x00, 0x00, // bmAttributes, LIBUSB_BM_LPM_SUPPORT = 2 and its the only option + + // ------------------------------------------------- + // WebUSB descriptor + // header + 0x18, // bLength, Size of this descriptor. Must be set to 24. + 0x10, // bDescriptorType, DEVICE CAPABILITY descriptor + 0x05, // bDevCapabilityType, PLATFORM capability + 0x00, // bReserved, This field is reserved and shall be set to zero. + + // PlatformCapabilityUUID, Must be set to {3408b638-09a9-47a0-8bfd-a0768815b665}. + 0x38, 0xB6, 0x08, 0x34, + 0xA9, 0x09, 0xA0, 0x47, + 0x8B, 0xFD, 0xA0, 0x76, + 0x88, 0x15, 0xB6, 0x65, + // + + 0x00, 0x01, // bcdVersion, Protocol version supported. Must be set to 0x0100. + WEBUSB_VENDOR_CODE, // bVendorCode, bRequest value used for issuing WebUSB requests. + // there used to be a concept of "allowed origins", but it was removed from the spec + // it was intended to be a security feature, but then the entire security model relies on domain ownership + // https://github.com/WICG/webusb/issues/49 + // other implementations use various other indexed to leverate this no-longer-valid feature. we wont. + // the spec says we *must* reply to index 0x03 with the url, so we'll hint that that's the right index + 0x03, // iLandingPage, URL descriptor index of the device’s landing page. + + // ------------------------------------------------- + // WinUSB descriptor + // header + 0x1C, // Descriptor size (28 bytes) + 0x10, // Descriptor type (Device Capability) + 0x05, // Capability type (Platform) + 0x00, // Reserved + + // MS OS 2.0 Platform Capability ID (D8DD60DF-4589-4CC7-9CD2-659D9E648A9F) + // Indicates the device supports the Microsoft OS 2.0 descriptor + 0xDF, 0x60, 0xDD, 0xD8, + 0x89, 0x45, 0xC7, 0x4C, + 0x9C, 0xD2, 0x65, 0x9D, + 0x9E, 0x64, 0x8A, 0x9F, + + 0x00, 0x00, 0x03, 0x06, // Windows version, currently set to 8.1 (0x06030000) + + WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // MS OS 2.0 descriptor size (word) + MS_VENDOR_CODE, 0x00 // vendor code, no alternate enumeration +}; + +uint8_t webusb_url_descriptor[] = { + 0x14, /* bLength */ + WEBUSB_DESC_TYPE_URL, // bDescriptorType + WEBUSB_URL_SCHEME_HTTPS, // bScheme + 'u', 's', 'b', 'p', 'a', 'n', 'd', 'a', '.', 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' +}; + +// WinUSB 2.0 descriptor. This is what modern systems use +// https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c +// http://janaxelson.com/files/ms_os_20_descriptors.c +// https://books.google.com/books?id=pkefBgAAQBAJ&pg=PA353&lpg=PA353 +uint8_t winusb_20_desc[WINUSB_PLATFORM_DESCRIPTOR_LENGTH] = { + // Microsoft OS 2.0 descriptor set header (table 10) + 0x0A, 0x00, // Descriptor size (10 bytes) + 0x00, 0x00, // MS OS 2.0 descriptor set header + + 0x00, 0x00, 0x03, 0x06, // Windows version (8.1) (0x06030000) + WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // Total size of MS OS 2.0 descriptor set + + // Microsoft OS 2.0 compatible ID descriptor + 0x14, 0x00, // Descriptor size (20 bytes) + 0x03, 0x00, // MS OS 2.0 compatible ID descriptor + 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Sub-compatible ID + + // Registry property descriptor + 0x80, 0x00, // Descriptor size (130 bytes) + 0x04, 0x00, // Registry Property descriptor + 0x01, 0x00, // Strings are null-terminated Unicode + 0x28, 0x00, // Size of Property Name (40 bytes) "DeviceInterfaceGUID" + + // bPropertyName (DeviceInterfaceGUID) + 'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00, + 't', 0x00, 'e', 0x00, 'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00, + 'U', 0x00, 'I', 0x00, 'D', 0x00, 0x00, 0x00, + + 0x4E, 0x00, // Size of Property Data (78 bytes) + + // Vendor-defined property data: {CCE5291C-A69F-4995-A4C2-2AE57A51ADE9} + '{', 0x00, 'c', 0x00, 'c', 0x00, 'e', 0x00, '5', 0x00, '2', 0x00, '9', 0x00, '1', 0x00, // 16 + 'c', 0x00, '-', 0x00, 'a', 0x00, '6', 0x00, '9', 0x00, 'f', 0x00, '-', 0x00, '4', 0x00, // 32 + '9', 0x00, '9', 0x00, '5', 0x00, '-', 0x00, 'a', 0x00, '4', 0x00, 'c', 0x00, '2', 0x00, // 48 + '-', 0x00, '2', 0x00, 'a', 0x00, 'e', 0x00, '5', 0x00, '7', 0x00, 'a', 0x00, '5', 0x00, // 64 + '1', 0x00, 'a', 0x00, 'd', 0x00, 'e', 0x00, '9', 0x00, '}', 0x00, 0x00, 0x00 // 78 bytes +}; + +#endif + // current packet USB_Setup_TypeDef setup; uint8_t usbdata[0x100]; +uint8_t* ep0_txdata = NULL; +uint16_t ep0_txlen = 0; // Store the current interface alt setting. int current_int0_alt_setting = 0; @@ -206,6 +405,26 @@ void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) { } } +// IN EP 0 TX FIFO has a max size of 127 bytes (much smaller than the rest) +// so use TX FIFO empty interrupt to send larger amounts of data +void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { + #ifdef DEBUG_USB + puts("writing "); + hexdump(src, len); + #endif + + uint16_t wplen = min(len, 0x40); + USB_WritePacket(src, wplen, 0); + + if (wplen < len) { + ep0_txdata = src + wplen; + ep0_txlen = len - wplen; + USBx_DEVICE->DIEPEMPMSK |= 1; + } else { + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } +} + void usb_reset() { // unmask endpoint interrupts, so many sets USBx_DEVICE->DAINT = 0xFFFFFFFF; @@ -315,18 +534,22 @@ void usb_setup() { USB_WritePacket(configuration_desc, min(sizeof(configuration_desc), setup.b.wLength.w), 0); USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; break; + case USB_DESC_TYPE_DEVICE_QUALIFIER: + USB_WritePacket(device_qualifier, min(sizeof(device_qualifier), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; case USB_DESC_TYPE_STRING: switch (setup.b.wValue.bw.msb) { - case 0: - USB_WritePacket((uint8_t*)string_0_desc, min(sizeof(string_0_desc), setup.b.wLength.w), 0); + case STRING_OFFSET_LANGID: + USB_WritePacket((uint8_t*)string_language_desc, min(sizeof(string_language_desc), setup.b.wLength.w), 0); break; - case 1: - USB_WritePacket((uint8_t*)string_1_desc, min(sizeof(string_1_desc), setup.b.wLength.w), 0); + case STRING_OFFSET_IMANUFACTURER: + USB_WritePacket((uint8_t*)string_manufacturer_desc, min(sizeof(string_manufacturer_desc), setup.b.wLength.w), 0); break; - case 2: - USB_WritePacket((uint8_t*)string_2_desc, min(sizeof(string_2_desc), setup.b.wLength.w), 0); + case STRING_OFFSET_IPRODUCT: + USB_WritePacket((uint8_t*)string_product_desc, min(sizeof(string_product_desc), setup.b.wLength.w), 0); break; - case 3: + case STRING_OFFSET_ISERIAL: #ifdef PANDA resp[0] = 0x02 + 12*4; resp[1] = 0x03; @@ -342,9 +565,17 @@ void usb_setup() { USB_WritePacket(resp, min(resp[0], setup.b.wLength.w), 0); #else - USB_WritePacket((const uint8_t *)string_3_desc, min(sizeof(string_3_desc), setup.b.wLength.w), 0); + USB_WritePacket((const uint8_t *)string_serial_desc, min(sizeof(string_serial_desc), setup.b.wLength.w), 0); #endif break; + #ifdef PANDA + case STRING_OFFSET_ICONFIGURATION: + USB_WritePacket((uint8_t*)string_configuration_desc, min(sizeof(string_configuration_desc), setup.b.wLength.w), 0); + break; + case 238: + USB_WritePacket((uint8_t*)string_238_desc, min(sizeof(string_238_desc), setup.b.wLength.w), 0); + break; + #endif default: // nothing USB_WritePacket(0, 0, 0); @@ -352,6 +583,12 @@ void usb_setup() { } USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; break; + #ifdef PANDA + case USB_DESC_TYPE_BINARY_OBJECT_STORE: + USB_WritePacket(binary_object_store_desc, min(sizeof(binary_object_store_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + #endif default: // nothing here? USB_WritePacket(0, 0, 0); @@ -372,6 +609,39 @@ void usb_setup() { USB_WritePacket(0, 0, 0); USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; break; + #ifdef PANDA + case WEBUSB_VENDOR_CODE: + switch (setup.b.wIndex.w) { + case WEBUSB_REQ_GET_URL: + USB_WritePacket(webusb_url_descriptor, min(sizeof(webusb_url_descriptor), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + default: + // probably asking for allowed origins, which was removed from the spec + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + } + break; + case MS_VENDOR_CODE: + switch (setup.b.wIndex.w) { + // winusb 2.0 descriptor from BOS + case WINUSB_REQ_GET_DESCRIPTOR: + USB_WritePacket_EP0((uint8_t*)winusb_20_desc, min(sizeof(winusb_20_desc), setup.b.wLength.w)); + break; + // Extended Compat ID OS Descriptor + case WINUSB_REQ_GET_COMPATID_DESCRIPTOR: + USB_WritePacket_EP0((uint8_t*)winusb_ext_compatid_os_desc, min(sizeof(winusb_ext_compatid_os_desc), setup.b.wLength.w)); + break; + // Extended Properties OS Descriptor + case WINUSB_REQ_GET_EXT_PROPS_OS: + USB_WritePacket_EP0((uint8_t*)winusb_ext_prop_os_desc, min(sizeof(winusb_ext_prop_os_desc), setup.b.wLength.w)); + break; + default: + USB_WritePacket_EP0(0, 0); + } + break; + #endif default: resp_len = usb_cb_control_msg(&setup, resp, 1); USB_WritePacket(resp, min(resp_len, setup.b.wLength.w), 0); @@ -682,6 +952,24 @@ void usb_irqhandler(void) { break; } + if (USBx_INEP(0)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) { + #ifdef DEBUG_USB + puts(" IN PACKET QUEUE\n"); + #endif + + if (ep0_txlen != 0 && (USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40) { + uint16_t len = min(ep0_txlen, 0x40); + USB_WritePacket(ep0_txdata, len, 0); + ep0_txdata += len; + ep0_txlen -= len; + if (ep0_txlen == 0) { + ep0_txdata = NULL; + USBx_DEVICE->DIEPEMPMSK &= ~1; + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } + } + } + // clear interrupts USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0? USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT; diff --git a/panda/board/get_sdk.sh b/panda/board/get_sdk.sh index 2248d1b9ec49ba..7b8d1f9154c0ac 100755 --- a/panda/board/get_sdk.sh +++ b/panda/board/get_sdk.sh @@ -1,3 +1,3 @@ #!/bin/bash sudo apt-get install gcc-arm-none-eabi python-pip -sudo pip2 install libusb1 +sudo pip2 install libusb1 pycrypto requests diff --git a/panda/board/get_sdk_mac.sh b/panda/board/get_sdk_mac.sh old mode 100644 new mode 100755 index 1c4c74ff8c037b..a6f641dce12116 --- a/panda/board/get_sdk_mac.sh +++ b/panda/board/get_sdk_mac.sh @@ -2,4 +2,4 @@ # Need formula for gcc brew tap ArmMbed/homebrew-formulae brew install python dfu-util arm-none-eabi-gcc -pip2 install libusb1 +pip2 install libusb1 pycrypto requests diff --git a/panda/board/gpio.h b/panda/board/gpio.h index 0e15e3ba4578d7..6112f6f887c703 100644 --- a/panda/board/gpio.h +++ b/panda/board/gpio.h @@ -15,6 +15,7 @@ int has_external_debug_serial = 0; int is_giant_panda = 0; int is_entering_bootmode = 0; int revision = PANDA_REV_AB; +int is_grey_panda = 0; int detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { set_gpio_mode(GPIO, pin, MODE_INPUT); @@ -45,9 +46,14 @@ void detect() { // check if the ESP is trying to put me in boot mode is_entering_bootmode = !detect_with_pull(GPIOB, 0, PULL_UP); + + // check if it's a grey panda by seeing if the SPI lines are floating + // TODO: is this reliable? + is_grey_panda = !(detect_with_pull(GPIOA, 4, PULL_DOWN) | detect_with_pull(GPIOA, 5, PULL_DOWN) | detect_with_pull(GPIOA, 6, PULL_DOWN) | detect_with_pull(GPIOA, 7, PULL_DOWN)); #else // need to do this for early detect is_giant_panda = 0; + is_grey_panda = 0; revision = PANDA_REV_AB; is_entering_bootmode = 0; #endif @@ -66,8 +72,15 @@ void clock_init() { RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE; #else - RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | - RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE; + #ifdef PEDAL + // comma pedal has a 16mhz crystal + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE; + #else + // NEO board has a 8mhz crystal + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE; + #endif #endif // start PLL @@ -106,7 +119,7 @@ void periph_init() { RCC->APB1ENR |= RCC_APB1ENR_DACEN; RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; - //RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; + RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; RCC->APB2ENR |= RCC_APB2ENR_USART1EN; RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; @@ -126,8 +139,13 @@ void set_can_enable(CAN_TypeDef *CAN, int enabled) { // CAN1_EN set_gpio_output(GPIOC, 1, !enabled); #else - // CAN1_EN - set_gpio_output(GPIOB, 3, enabled); + #ifdef PEDAL + // CAN1_EN (not flipped) + set_gpio_output(GPIOB, 3, !enabled); + #else + // CAN1_EN + set_gpio_output(GPIOB, 3, enabled); + #endif #endif } else if (CAN == CAN2) { #ifdef PANDA @@ -279,6 +297,14 @@ void gpio_init() { set_gpio_mode(GPIOC, 2, MODE_ANALOG); set_gpio_mode(GPIOC, 3, MODE_ANALOG); +#ifdef PEDAL + // comma pedal has inputs on C0 and C1 + set_gpio_mode(GPIOC, 0, MODE_ANALOG); + set_gpio_mode(GPIOC, 1, MODE_ANALOG); + // DAC outputs on A4 and A5 + // apparently they don't need GPIO setup +#endif + // C8: FAN aka TIM3_CH4 set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); @@ -437,9 +463,10 @@ void early() { if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { + #ifdef PANDA set_esp_mode(ESP_DISABLED); + #endif set_led(LED_GREEN, 1); - jump_to_bootloader(); } diff --git a/panda/board/main.c b/panda/board/main.c index 402fd73e2bdaf2..8bb6a0cee09681 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -15,6 +15,7 @@ #include "drivers/uart.h" #include "drivers/adc.h" #include "drivers/usb.h" +#include "drivers/gmlan_alt.h" #include "drivers/can.h" #include "drivers/spi.h" #include "drivers/timer.h" @@ -104,7 +105,14 @@ int get_health_pkt(void *dat) { #ifdef PANDA health->current = adc_get(ADCCHAN_CURRENT); - health->started = (GPIOA->IDR & (1 << 1)) == 0; + int safety_ignition = safety_ignition_hook(); + if (safety_ignition < 0) { + //Use the GPIO pin to determine ignition + health->started = (GPIOA->IDR & (1 << 1)) == 0; + } else { + //Current safety hooks want to determine ignition (ex: GM) + health->started = safety_ignition; + } #else health->current = 0; health->started = (GPIOC->IDR & (1 << 13)) != 0; @@ -175,6 +183,11 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { puts(" err: "); puth(can_err_cnt); puts("\n"); break; + // **** 0xc1: is grey panda + case 0xc1: + resp[0] = is_grey_panda; + resp_len = 1; + break; // **** 0xd0: fetch serial number case 0xd0: #ifdef PANDA @@ -229,6 +242,8 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { case 0xd9: if (setup->b.wValue.w == 1) { set_esp_mode(ESP_ENABLED); + } else if (setup->b.wValue.w == 2) { + set_esp_mode(ESP_BOOTMODE); } else { set_esp_mode(ESP_DISABLED); } @@ -267,16 +282,22 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { // and it's blocked over WiFi // Allow ELM security mode to be set over wifi. if (hardwired || setup->b.wValue.w == SAFETY_NOOUTPUT || setup->b.wValue.w == SAFETY_ELM327) { - safety_set_mode(setup->b.wValue.w); + safety_set_mode(setup->b.wValue.w, (int16_t)setup->b.wIndex.w); switch (setup->b.wValue.w) { case SAFETY_NOOUTPUT: can_silent = ALL_CAN_SILENT; break; case SAFETY_ELM327: can_silent = ALL_CAN_BUT_MAIN_SILENT; + can_autobaud_enabled[0] = false; break; default: can_silent = ALL_CAN_LIVE; + can_autobaud_enabled[0] = false; + can_autobaud_enabled[1] = false; + #ifdef PANDA + can_autobaud_enabled[2] = false; + #endif break; } can_init_all(); @@ -296,6 +317,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { // **** 0xde: set can bitrate case 0xde: if (setup->b.wValue.w < BUS_MAX) { + can_autobaud_enabled[setup->b.wValue.w] = false; can_speed[setup->b.wValue.w] = setup->b.wIndex.w; can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); } @@ -304,6 +326,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { case 0xe0: ur = get_ring_by_number(setup->b.wValue.w); if (!ur) break; + if (ur == &esp_ring) uart_dma_drain(); // read while ((resp_len < min(setup->b.wLength.w, MAX_RESP_LEN)) && getc(ur, (char*)&resp[resp_len])) { @@ -468,6 +491,11 @@ void __initialize_hardware_early() { early(); } +void __attribute__ ((noinline)) enable_fpu() { + // enable the FPU + SCB->CPACR |= ((3UL << 10*2) | (3UL << 11*2)); +} + int main() { // shouldn't have interrupts here, but just in case __disable_irq(); @@ -489,9 +517,15 @@ int main() { #endif puts(has_external_debug_serial ? " real serial\n" : " USB serial\n"); puts(is_giant_panda ? " GIANTpanda detected\n" : " not GIANTpanda\n"); + puts(is_grey_panda ? " gray panda detected!\n" : " white panda\n"); puts(is_entering_bootmode ? " ESP wants bootmode\n" : " no bootmode\n"); gpio_init(); +#ifdef PANDA + // panda has an FPU, let's use it! + enable_fpu(); +#endif + // enable main uart if it's connected if (has_external_debug_serial) { // WEIRDNESS: without this gate around the UART, it would "crash", but only if the ESP is enabled @@ -500,9 +534,12 @@ int main() { } #ifdef PANDA - // enable ESP uart - uart_init(USART1, 115200); - + if (is_grey_panda) { + uart_init(USART1, 9600); + } else { + // enable ESP uart + uart_init(USART1, 115200); + } // enable LIN uart_init(UART5, 10400); UART5->CR2 |= USART_CR2_LINEN; @@ -522,7 +559,7 @@ int main() { usb_init(); // default to silent mode to prevent issues with Ford - safety_set_mode(SAFETY_NOOUTPUT); + safety_set_mode(SAFETY_NOOUTPUT, 0); can_silent = ALL_CAN_SILENT; can_init_all(); @@ -540,6 +577,11 @@ int main() { __enable_irq(); + // if the error interrupt is enabled to quickly when the CAN bus is active + // something bad happens and you can't connect to the device over USB + delay(10000000); + CAN1->IER |= CAN_IER_ERRIE | CAN_IER_LECIE; + // LED should keep on blinking all the time uint64_t cnt = 0; @@ -552,6 +594,8 @@ int main() { for (cnt=0;;cnt++) { can_live = pending_can_live; + //puth(usart1_dma); puts(" "); puth(DMA2_Stream5->M0AR); puts(" "); puth(DMA2_Stream5->NDTR); puts("\n"); + #ifdef PANDA int current = adc_get(ADCCHAN_CURRENT); diff --git a/panda/board/pedal/.gitignore b/panda/board/pedal/.gitignore new file mode 100644 index 00000000000000..94053f2925089b --- /dev/null +++ b/panda/board/pedal/.gitignore @@ -0,0 +1 @@ +obj/* diff --git a/panda/board/pedal/Makefile b/panda/board/pedal/Makefile new file mode 100644 index 00000000000000..9917e381503b03 --- /dev/null +++ b/panda/board/pedal/Makefile @@ -0,0 +1,59 @@ +# :set noet +PROJ_NAME = comma + +CFLAGS = -O2 -Wall -std=gnu11 -DPEDAL +CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3 +CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx +CFLAGS += -I ../inc -I ../ -I ../../ -nostdlib +CFLAGS += -T../stm32_flash.ld + +STARTUP_FILE = startup_stm32f205xx + +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy +OBJDUMP = arm-none-eabi-objdump +DFU_UTIL = "dfu-util" + +# pedal only uses the debug cert +CERT = ../../certs/debug +CFLAGS += "-DALLOW_DEBUG" + +canflash: obj/$(PROJ_NAME).bin + ../../tests/pedal/enter_canloader.py $< + +usbflash: obj/$(PROJ_NAME).bin + ../../tests/pedal/enter_canloader.py; sleep 0.5 + PYTHONPATH=../../ python -c "from python import Panda; p = [x for x in [Panda(x) for x in Panda.list()] if x.bootstub]; assert(len(p)==1); p[0].flash('obj/$(PROJ_NAME).bin', reconnect=False)" + +recover: obj/bootstub.bin obj/$(PROJ_NAME).bin + ../../tests/pedal/enter_canloader.py --recover; sleep 0.5 + $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin + $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.bin + +obj/main.o: main.c ../*.h + mkdir -p obj + $(CC) $(CFLAGS) -o $@ -c $< + +obj/bootstub.o: ../bootstub.c ../*.h + mkdir -p obj + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(STARTUP_FILE).o: ../$(STARTUP_FILE).s + $(CC) $(CFLAGS) -o $@ -c $< + +obj/%.o: ../../crypto/%.c + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.o + # hack + $(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin + SETLEN=1 ../../crypto/sign.py obj/code.bin $@ $(CERT) + +obj/bootstub.bin: obj/$(STARTUP_FILE).o obj/bootstub.o obj/sha.o obj/rsa.o + $(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@ + +clean: + rm -f obj/* + diff --git a/panda/board/pedal/README b/panda/board/pedal/README new file mode 100644 index 00000000000000..cf779db258fe14 --- /dev/null +++ b/panda/board/pedal/README @@ -0,0 +1,28 @@ +This is the firmware for the comma pedal. It borrows a lot from panda. + +The comma pedal is a gas pedal interceptor for Honda/Acura. It allows you to "virtually" press the pedal. + +This is the open source software. Note that it is not ready to use yet. + +== Test Plan == + +* Startup +** Confirm STATE_FAULT_STARTUP +* Timeout +** Send value +** Confirm value is output +** Stop sending messages +** Confirm value is passthru after 100ms +** Confirm STATE_FAULT_TIMEOUT +* Random values +** Send random 6 byte messages +** Confirm random values cause passthru +** Confirm STATE_FAULT_BAD_CHECKSUM +* Same message lockout +** Send same message repeated +** Confirm timeout behavior +* Don't set enable +** Confirm no output +* Set enable and values +** Confirm output + diff --git a/panda/board/pedal/main.c b/panda/board/pedal/main.c new file mode 100644 index 00000000000000..5d5264791ccf54 --- /dev/null +++ b/panda/board/pedal/main.c @@ -0,0 +1,295 @@ +//#define DEBUG +//#define CAN_LOOPBACK_MODE +//#define USE_INTERNAL_OSC + +#include "../config.h" + +#include "drivers/drivers.h" +#include "drivers/llgpio.h" +#include "gpio.h" + +#define CUSTOM_CAN_INTERRUPTS + +#include "libc.h" +#include "safety.h" +#include "drivers/adc.h" +#include "drivers/uart.h" +#include "drivers/dac.h" +#include "drivers/can.h" +#include "drivers/timer.h" + +#define CAN CAN1 + +//#define PEDAL_USB + +#ifdef PEDAL_USB + #include "drivers/usb.h" +#endif + +#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef +uint32_t enter_bootloader_mode; + +void __initialize_hardware_early() { + early(); +} + +// ********************* serial debugging ********************* + +void debug_ring_callback(uart_ring *ring) { + char rcv; + while (getc(ring, &rcv)) { + putc(ring, rcv); + } +} + +#ifdef PEDAL_USB + +int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) { return 0; } +void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired) {} +void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) {} +void usb_cb_enumeration_complete() {} + +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { + int resp_len = 0; + uart_ring *ur = NULL; + switch (setup->b.bRequest) { + // **** 0xe0: uart read + case 0xe0: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) break; + if (ur == &esp_ring) uart_dma_drain(); + // read + while ((resp_len < min(setup->b.wLength.w, MAX_RESP_LEN)) && + getc(ur, (char*)&resp[resp_len])) { + ++resp_len; + } + break; + } + return resp_len; +} + +#endif + +// ***************************** honda can checksum ***************************** + +int can_cksum(uint8_t *dat, int len, int addr, int idx) { + int i; + int s = 0; + for (i = 0; i < len; i++) { + s += (dat[i] >> 4); + s += dat[i] & 0xF; + } + s += (addr>>0)&0xF; + s += (addr>>4)&0xF; + s += (addr>>8)&0xF; + s += idx; + s = 8-s; + return s&0xF; +} + +// ***************************** can port ***************************** + +// addresses to be used on CAN +#define CAN_GAS_INPUT 0x200 +#define CAN_GAS_OUTPUT 0x201 + +void CAN1_TX_IRQHandler() { + // clear interrupt + CAN->TSR |= CAN_TSR_RQCP0; +} + +// two independent values +uint16_t gas_set_0 = 0; +uint16_t gas_set_1 = 0; + +#define MAX_TIMEOUT 10 +uint32_t timeout = 0; +uint32_t current_index = 0; + +#define NO_FAULT 0 +#define FAULT_BAD_CHECKSUM 1 +#define FAULT_SEND 2 +#define FAULT_SCE 3 +#define FAULT_STARTUP 4 +#define FAULT_TIMEOUT 5 +#define FAULT_INVALID 6 +uint8_t state = FAULT_STARTUP; + +void CAN1_RX0_IRQHandler() { + while (CAN->RF0R & CAN_RF0R_FMP0) { + #ifdef DEBUG + puts("CAN RX\n"); + #endif + uint32_t address = CAN->sFIFOMailBox[0].RIR>>21; + if (address == CAN_GAS_INPUT) { + // softloader entry + if (CAN->sFIFOMailBox[0].RDLR == 0xdeadface) { + if (CAN->sFIFOMailBox[0].RDHR == 0x0ab00b1e) { + enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; + NVIC_SystemReset(); + } else if (CAN->sFIFOMailBox[0].RDHR == 0x02b00b1e) { + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + } + } + + // normal packet + uint8_t *dat = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR; + uint8_t *dat2 = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR; + uint16_t value_0 = (dat[0] << 8) | dat[1]; + uint16_t value_1 = (dat[2] << 8) | dat[3]; + uint8_t enable = (dat2[0] >> 7) & 1; + uint8_t index = (dat2[1] >> 4) & 3; + if (can_cksum(dat, 5, CAN_GAS_INPUT, index) == (dat2[1] & 0xF)) { + if (((current_index+1)&3) == index) { + #ifdef DEBUG + puts("setting gas "); + puth(value); + puts("\n"); + #endif + if (enable) { + gas_set_0 = value_0; + gas_set_1 = value_1; + } else { + // clear the fault state if values are 0 + if (value_0 == 0 && value_1 == 0) { + state = NO_FAULT; + } else { + state = FAULT_INVALID; + } + gas_set_0 = gas_set_1 = 0; + } + // clear the timeout + timeout = 0; + } + current_index = index; + } else { + // wrong checksum = fault + state = FAULT_BAD_CHECKSUM; + } + } + // next + CAN->RF0R |= CAN_RF0R_RFOM0; + } +} + +void CAN1_SCE_IRQHandler() { + state = FAULT_SCE; + can_sce(CAN); +} + +int pdl0 = 0, pdl1 = 0; +int pkt_idx = 0; + +int led_value = 0; + +void TIM3_IRQHandler() { + #ifdef DEBUG + puth(TIM3->CNT); + puts(" "); + puth(pdl0); + puts(" "); + puth(pdl1); + puts("\n"); + #endif + + // check timer for sending the user pedal and clearing the CAN + if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { + uint8_t dat[8]; + dat[0] = (pdl0>>8)&0xFF; + dat[1] = (pdl0>>0)&0xFF; + dat[2] = (pdl1>>8)&0xFF; + dat[3] = (pdl1>>0)&0xFF; + dat[4] = state; + dat[5] = can_cksum(dat, 5, CAN_GAS_OUTPUT, pkt_idx) | (pkt_idx<<4); + CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1]<<8) | (dat[2]<<16) | (dat[3]<<24); + CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5]<<8); + CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5 + CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1; + ++pkt_idx; + pkt_idx &= 3; + } else { + // old can packet hasn't sent! + state = FAULT_SEND; + #ifdef DEBUG + puts("CAN MISS\n"); + #endif + } + + // blink the LED + set_led(LED_GREEN, led_value); + led_value = !led_value; + + TIM3->SR = 0; + + // up timeout for gas set + if (timeout == MAX_TIMEOUT) { + state = FAULT_TIMEOUT; + } else { + timeout += 1; + } +} + +// ***************************** main code ***************************** + +void pedal() { + // read/write + pdl0 = adc_get(ADCCHAN_ACCEL0); + pdl1 = adc_get(ADCCHAN_ACCEL1); + + // write the pedal to the DAC + if (state == NO_FAULT) { + dac_set(0, max(gas_set_0, pdl0)); + dac_set(1, max(gas_set_1, pdl1)); + } else { + dac_set(0, pdl0); + dac_set(1, pdl1); + } + + // feed the watchdog + IWDG->KR = 0xAAAA; +} + +int main() { + __disable_irq(); + + // init devices + clock_init(); + periph_init(); + gpio_init(); + +#ifdef PEDAL_USB + // enable USB + usb_init(); +#endif + + // pedal stuff + dac_init(); + adc_init(); + + // init can + can_silent = ALL_CAN_LIVE; + can_init(0); + + // 48mhz / 65536 ~= 732 + timer_init(TIM3, 15); + NVIC_EnableIRQ(TIM3_IRQn); + + // setup watchdog + IWDG->KR = 0x5555; + IWDG->PR = 0; // divider /4 + // 0 = 0.125 ms, let's have a 50ms watchdog + IWDG->RLR = 400 - 1; + IWDG->KR = 0xCCCC; + + puts("**** INTERRUPTS ON ****\n"); + __enable_irq(); + + // main pedal loop + while (1) { + pedal(); + } + + return 0; +} + diff --git a/selfdrive/radar/mock/__init__.py b/panda/board/pedal/obj/.gitkeep similarity index 100% rename from selfdrive/radar/mock/__init__.py rename to panda/board/pedal/obj/.gitkeep diff --git a/panda/board/safety.h b/panda/board/safety.h index dc4631f4606de8..4d2b46899f7969 100644 --- a/panda/board/safety.h +++ b/panda/board/safety.h @@ -1,17 +1,50 @@ +// sample struct that keeps 3 samples in memory +struct sample_t { + int values[6]; + int min; + int max; +} sample_t_default = {{0}, 0, 0}; + +// no float support in STM32F2 micros (cortex-m3) +#ifdef PANDA +struct lookup_t { + float x[3]; + float y[3]; +}; +#endif + void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); int safety_tx_lin_hook(int lin_num, uint8_t *data, int len); +int safety_ignition_hook(); +uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last); +int to_signed(int d, int bits); +void update_sample(struct sample_t *sample, int sample_new); +int max_limit_check(int val, const int MAX, const int MIN); +int dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, + const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR); +int driver_limit_check(int val, int val_last, struct sample_t *val_driver, + const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, + const int MAX_ALLOWANCE, const int DRIVER_FACTOR); +int rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA); +#ifdef PANDA +float interpolate(struct lookup_t xy, float x); +#endif -typedef void (*safety_hook_init)(); +typedef void (*safety_hook_init)(int16_t param); typedef void (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push); typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send); typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len); +typedef int (*ign_hook)(); +typedef int (*fwd_hook)(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd); typedef struct { safety_hook_init init; + ign_hook ignition; rx_hook rx; tx_hook tx; tx_lin_hook tx_lin; + fwd_hook fwd; } safety_hooks; // This can be set by the safety hooks. @@ -21,6 +54,15 @@ int controls_allowed = 0; #include "safety/safety_defaults.h" #include "safety/safety_honda.h" #include "safety/safety_toyota.h" +#ifdef PANDA +#include "safety/safety_toyota_ipas.h" +#include "safety/safety_tesla.h" +#endif +#include "safety/safety_gm.h" +#include "safety/safety_ford.h" +#include "safety/safety_cadillac.h" +#include "safety/safety_hyundai.h" +#include "safety/safety_chrysler.h" #include "safety/safety_elm327.h" const safety_hooks *current_hooks = &nooutput_hooks; @@ -37,6 +79,16 @@ int safety_tx_lin_hook(int lin_num, uint8_t *data, int len){ return current_hooks->tx_lin(lin_num, data, len); } +// -1 = Disabled (Use GPIO to determine ignition) +// 0 = Off (not started) +// 1 = On (started) +int safety_ignition_hook() { + return current_hooks->ignition(); +} +int safety_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return current_hooks->fwd(bus_num, to_fwd); +} + typedef struct { uint16_t id; const safety_hooks *hooks; @@ -45,6 +97,14 @@ typedef struct { #define SAFETY_NOOUTPUT 0 #define SAFETY_HONDA 1 #define SAFETY_TOYOTA 2 +#define SAFETY_GM 3 +#define SAFETY_HONDA_BOSCH 4 +#define SAFETY_FORD 5 +#define SAFETY_CADILLAC 6 +#define SAFETY_HYUNDAI 7 +#define SAFETY_TESLA 8 +#define SAFETY_CHRYSLER 9 +#define SAFETY_TOYOTA_IPAS 0x1335 #define SAFETY_TOYOTA_NOLIMITS 0x1336 #define SAFETY_ALLOUTPUT 0x1337 #define SAFETY_ELM327 0xE327 @@ -52,22 +112,140 @@ typedef struct { const safety_hook_config safety_hook_registry[] = { {SAFETY_NOOUTPUT, &nooutput_hooks}, {SAFETY_HONDA, &honda_hooks}, + {SAFETY_HONDA_BOSCH, &honda_bosch_hooks}, {SAFETY_TOYOTA, &toyota_hooks}, + {SAFETY_GM, &gm_hooks}, + {SAFETY_FORD, &ford_hooks}, + {SAFETY_CADILLAC, &cadillac_hooks}, + {SAFETY_HYUNDAI, &hyundai_hooks}, + {SAFETY_CHRYSLER, &chrysler_hooks}, {SAFETY_TOYOTA_NOLIMITS, &toyota_nolimits_hooks}, +#ifdef PANDA + {SAFETY_TOYOTA_IPAS, &toyota_ipas_hooks}, + {SAFETY_TESLA, &tesla_hooks}, +#endif {SAFETY_ALLOUTPUT, &alloutput_hooks}, {SAFETY_ELM327, &elm327_hooks}, }; #define HOOK_CONFIG_COUNT (sizeof(safety_hook_registry)/sizeof(safety_hook_config)) -int safety_set_mode(uint16_t mode) { +int safety_set_mode(uint16_t mode, int16_t param) { for (int i = 0; i < HOOK_CONFIG_COUNT; i++) { if (safety_hook_registry[i].id == mode) { current_hooks = safety_hook_registry[i].hooks; - if (current_hooks->init) current_hooks->init(); + if (current_hooks->init) current_hooks->init(param); return 0; } } return -1; } +// compute the time elapsed (in microseconds) from 2 counter samples +uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last) { + return ts > ts_last ? ts - ts_last : (0xFFFFFFFF - ts_last) + 1 + ts; +} + +// convert a trimmed integer to signed 32 bit int +int to_signed(int d, int bits) { + if (d >= (1 << (bits - 1))) { + d -= (1 << bits); + } + return d; +} + +// given a new sample, update the smaple_t struct +void update_sample(struct sample_t *sample, int sample_new) { + for (int i = sizeof(sample->values)/sizeof(sample->values[0]) - 1; i > 0; i--) { + sample->values[i] = sample->values[i-1]; + } + sample->values[0] = sample_new; + + // get the minimum and maximum measured samples + sample->min = sample->max = sample->values[0]; + for (int i = 1; i < sizeof(sample->values)/sizeof(sample->values[0]); i++) { + if (sample->values[i] < sample->min) sample->min = sample->values[i]; + if (sample->values[i] > sample->max) sample->max = sample->values[i]; + } +} + +int max_limit_check(int val, const int MAX, const int MIN) { + return (val > MAX) || (val < MIN); +} + +// check that commanded value isn't too far from measured +int dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, + const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR) { + + // *** val rate limit check *** + int highest_allowed_val = max(val_last, 0) + MAX_RATE_UP; + int lowest_allowed_val = min(val_last, 0) - MAX_RATE_UP; + + // if we've exceeded the meas val, we must start moving toward 0 + highest_allowed_val = min(highest_allowed_val, max(val_last - MAX_RATE_DOWN, max(val_meas->max, 0) + MAX_ERROR)); + lowest_allowed_val = max(lowest_allowed_val, min(val_last + MAX_RATE_DOWN, min(val_meas->min, 0) - MAX_ERROR)); + + // check for violation + return (val < lowest_allowed_val) || (val > highest_allowed_val); +} + +// check that commanded value isn't fighting against driver +int driver_limit_check(int val, int val_last, struct sample_t *val_driver, + const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, + const int MAX_ALLOWANCE, const int DRIVER_FACTOR) { + + int highest_allowed = max(val_last, 0) + MAX_RATE_UP; + int lowest_allowed = min(val_last, 0) - MAX_RATE_UP; + + int driver_max_limit = MAX + (MAX_ALLOWANCE + val_driver->max) * DRIVER_FACTOR; + int driver_min_limit = -MAX + (-MAX_ALLOWANCE + val_driver->min) * DRIVER_FACTOR; + + // if we've exceeded the applied torque, we must start moving toward 0 + highest_allowed = min(highest_allowed, max(val_last - MAX_RATE_DOWN, + max(driver_max_limit, 0))); + lowest_allowed = max(lowest_allowed, min(val_last + MAX_RATE_DOWN, + min(driver_min_limit, 0))); + + // check for violation + return (val < lowest_allowed) || (val > highest_allowed); +} + + +// real time check, mainly used for steer torque rate limiter +int rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { + + // *** torque real time rate limit check *** + int highest_val = max(val_last, 0) + MAX_RT_DELTA; + int lowest_val = min(val_last, 0) - MAX_RT_DELTA; + + // check for violation + return (val < lowest_val) || (val > highest_val); +} + + +#ifdef PANDA +// interp function that holds extreme values +float interpolate(struct lookup_t xy, float x) { + int size = sizeof(xy.x) / sizeof(xy.x[0]); + // x is lower than the first point in the x array. Return the first point + if (x <= xy.x[0]) { + return xy.y[0]; + + } else { + // find the index such that (xy.x[i] <= x < xy.x[i+1]) and linearly interp + for (int i=0; i < size-1; i++) { + if (x < xy.x[i+1]) { + float x0 = xy.x[i]; + float y0 = xy.y[i]; + float dx = xy.x[i+1] - x0; + float dy = xy.y[i+1] - y0; + // dx should not be zero as xy.x is supposed ot be monotonic + if (dx <= 0.) dx = 0.0001; + return dy * (x - x0) / dx + y0; + } + } + // if no such point is found, then x > xy.x[size-1]. Return last point + return xy.y[size - 1]; + } +} +#endif diff --git a/panda/board/safety/safety_cadillac.h b/panda/board/safety/safety_cadillac.h new file mode 100644 index 00000000000000..2a2d8b9857ff91 --- /dev/null +++ b/panda/board/safety/safety_cadillac.h @@ -0,0 +1,131 @@ +const int CADILLAC_MAX_STEER = 150; // 1s +// real time torque limit to prevent controls spamming +// the real time limit is 1500/sec +const int CADILLAC_MAX_RT_DELTA = 75; // max delta torque allowed for real time checks +const int32_t CADILLAC_RT_INTERVAL = 250000; // 250ms between real time checks +const int CADILLAC_MAX_RATE_UP = 2; +const int CADILLAC_MAX_RATE_DOWN = 5; +const int CADILLAC_DRIVER_TORQUE_ALLOWANCE = 50; +const int CADILLAC_DRIVER_TORQUE_FACTOR = 4; + +int cadillac_ign = 0; +int cadillac_cruise_engaged_last = 0; +int cadillac_rt_torque_last = 0; +int cadillac_desired_torque_last[4] = {0}; // 4 torque messages +uint32_t cadillac_ts_last = 0; +int cadillac_supercruise_on = 0; +struct sample_t cadillac_torque_driver; // last few driver torques measured + +int cadillac_get_torque_idx(uint32_t addr) { + if (addr==0x151) return 0; + else if (addr==0x152) return 1; + else if (addr==0x153) return 2; + else return 3; +} + +static void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr = to_push->RIR >> 21; + + if (addr == 356) { + int torque_driver_new = ((to_push->RDLR & 0x7) << 8) | ((to_push->RDLR >> 8) & 0xFF); + torque_driver_new = to_signed(torque_driver_new, 11); + // update array of samples + update_sample(&cadillac_torque_driver, torque_driver_new); + } + + // this message isn't all zeros when ignition is on + if (addr == 0x160 && bus_number == 0) { + cadillac_ign = to_push->RDLR > 0; + } + + // enter controls on rising edge of ACC, exit controls on ACC off + if ((addr == 0x370) && (bus_number == 0)) { + int cruise_engaged = to_push->RDLR & 0x800000; // bit 23 + if (cruise_engaged && !cadillac_cruise_engaged_last) { + controls_allowed = 1; + } else if (!cruise_engaged) { + controls_allowed = 0; + } + cadillac_cruise_engaged_last = cruise_engaged; + } + + // know supercruise mode and block openpilot msgs if on + if ((addr == 0x152) || (addr == 0x154)) { + cadillac_supercruise_on = (to_push->RDHR>>4) & 0x1; + } +} + +static int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + uint32_t addr = to_send->RIR >> 21; + + // steer cmd checks + if (addr == 0x151 || addr == 0x152 || addr == 0x153 || addr == 0x154) { + int desired_torque = ((to_send->RDLR & 0x3f) << 8) + ((to_send->RDLR & 0xff00) >> 8); + int violation = 0; + uint32_t ts = TIM2->CNT; + int idx = cadillac_get_torque_idx(addr); + desired_torque = to_signed(desired_torque, 14); + + if (controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, CADILLAC_MAX_STEER, -CADILLAC_MAX_STEER); + + // *** torque rate limit check *** + int desired_torque_last = cadillac_desired_torque_last[idx]; + violation |= driver_limit_check(desired_torque, desired_torque_last, &cadillac_torque_driver, + CADILLAC_MAX_STEER, CADILLAC_MAX_RATE_UP, CADILLAC_MAX_RATE_DOWN, + CADILLAC_DRIVER_TORQUE_ALLOWANCE, CADILLAC_DRIVER_TORQUE_FACTOR); + + // used next time + cadillac_desired_torque_last[idx] = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, cadillac_rt_torque_last, CADILLAC_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, cadillac_ts_last); + if (ts_elapsed > CADILLAC_RT_INTERVAL) { + cadillac_rt_torque_last = desired_torque; + cadillac_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + cadillac_desired_torque_last[idx] = 0; + cadillac_rt_torque_last = 0; + cadillac_ts_last = ts; + } + + if (violation || cadillac_supercruise_on) { + return false; + } + + } + return true; +} + +static void cadillac_init(int16_t param) { + controls_allowed = 0; + cadillac_ign = 0; +} + +static int cadillac_ign_hook() { + return cadillac_ign; +} + +const safety_hooks cadillac_hooks = { + .init = cadillac_init, + .rx = cadillac_rx_hook, + .tx = cadillac_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = cadillac_ign_hook, + .fwd = alloutput_fwd_hook, +}; diff --git a/panda/board/safety/safety_chrysler.h b/panda/board/safety/safety_chrysler.h new file mode 100644 index 00000000000000..eadc8eaa7c7231 --- /dev/null +++ b/panda/board/safety/safety_chrysler.h @@ -0,0 +1,136 @@ +// board enforces +// in-state +// ACC is active (green) +// out-state +// brake pressed +// stock LKAS ECU is online +// ACC is not active (white or disabled) + +// chrysler_: namespacing +int chrysler_speed = 0; + +// silence everything if stock ECUs are still online +int chrysler_lkas_detected = 0; +int chrysler_desired_torque_last = 0; + +static void chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } else { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 0x144 && bus_number == 0) { + chrysler_speed = ((to_push->RDLR & 0xFF000000) >> 16) | (to_push->RDHR & 0xFF); + } + + // check if stock LKAS ECU is still online + if (addr == 0x292 && bus_number == 0) { + chrysler_lkas_detected = 1; + controls_allowed = 0; + } + + // ["ACC_2"]['ACC_STATUS_2'] == 7 for active (green) Adaptive Cruise Control + if (addr == 0x1f4 && bus_number == 0) { + if (((to_push->RDLR & 0x380000) >> 19) == 7) { + controls_allowed = 1; + } else { + controls_allowed = 0; + } + } + + // exit controls on brake press by human + if (addr == 0x140) { + if (to_push->RDLR & 0x4) { + controls_allowed = 0; + } + } +} + +// if controls_allowed +// allow steering up to limit +// else +// block all commands that produce actuation +static int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + // There can be only one! (LKAS) + if (chrysler_lkas_detected) { + return 0; + } + + uint32_t addr; + if (to_send->RIR & 4) { + // Extended + addr = to_send->RIR >> 3; + } else { + // Normal + addr = to_send->RIR >> 21; + } + + // LKA STEER: Too large of values cause the steering actuator ECU to silently + // fault and no longer actuate the wheel until the car is rebooted. + if (addr == 0x292) { + int rdlr = to_send->RDLR; + int straight = 1024; + int steer = ((rdlr & 0x7) << 8) + ((rdlr & 0xFF00) >> 8) - straight; + int max_steer = 230; + int max_rate = 50; // ECU is fine with 100, but 3 is typical. + if (steer > max_steer) { + return false; + } + if (steer < -max_steer) { + return false; + } + if (!controls_allowed && steer != 0) { + // If controls not allowed, only allow steering to move closer to 0. + if (chrysler_desired_torque_last == 0) { + return false; + } + if ((chrysler_desired_torque_last > 0) && (steer >= chrysler_desired_torque_last)) { + return false; + } + if ((chrysler_desired_torque_last < 0) && (steer <= chrysler_desired_torque_last)) { + return false; + } + } + if (steer < (chrysler_desired_torque_last - max_rate)) { + return false; + } + if (steer > (chrysler_desired_torque_last + max_rate)) { + return false; + } + + chrysler_desired_torque_last = steer; + } + + // 1 allows the message through + return true; +} + +static int chrysler_tx_lin_hook(int lin_num, uint8_t *data, int len) { + // LIN is not used. + return false; +} + +static void chrysler_init(int16_t param) { + controls_allowed = 0; +} + +static int chrysler_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return -1; +} + +const safety_hooks chrysler_hooks = { + .init = chrysler_init, + .rx = chrysler_rx_hook, + .tx = chrysler_tx_hook, + .tx_lin = chrysler_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = chrysler_fwd_hook, +}; + diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 86155f32b9a68e..196df65d2f8eb6 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -1,8 +1,12 @@ void default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {} +int default_ign_hook() { + return -1; // use GPIO to determine ignition +} + // *** no output safety mode *** -static void nooutput_init() { +static void nooutput_init(int16_t param) { controls_allowed = 0; } @@ -14,16 +18,22 @@ static int nooutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { return false; } +static int nooutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return -1; +} + const safety_hooks nooutput_hooks = { .init = nooutput_init, .rx = default_rx_hook, .tx = nooutput_tx_hook, .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = nooutput_fwd_hook, }; // *** all output safety mode *** -static void alloutput_init() { +static void alloutput_init(int16_t param) { controls_allowed = 1; } @@ -35,10 +45,15 @@ static int alloutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { return true; } +static int alloutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return -1; +} + const safety_hooks alloutput_hooks = { .init = alloutput_init, .rx = default_rx_hook, .tx = alloutput_tx_hook, .tx_lin = alloutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = alloutput_fwd_hook, }; - diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h index ddacc27be0131f..98dce6532ac8ba 100644 --- a/panda/board/safety/safety_elm327.h +++ b/panda/board/safety/safety_elm327.h @@ -27,13 +27,19 @@ static int elm327_tx_lin_hook(int lin_num, uint8_t *data, int len) { return true; } -static void elm327_init() { +static void elm327_init(int16_t param) { controls_allowed = 1; } +static int elm327_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return -1; +} + const safety_hooks elm327_hooks = { .init = elm327_init, .rx = elm327_rx_hook, .tx = elm327_tx_hook, .tx_lin = elm327_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = elm327_fwd_hook, }; diff --git a/panda/board/safety/safety_ford.h b/panda/board/safety/safety_ford.h new file mode 100644 index 00000000000000..075029fb623e0f --- /dev/null +++ b/panda/board/safety/safety_ford.h @@ -0,0 +1,93 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// accel rising edge +// brake rising edge +// brake > 0mph + +int ford_brake_prev = 0; +int ford_gas_prev = 0; +int ford_is_moving = 0; + +static void ford_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + + if ((to_push->RIR>>21) == 0x217) { + // wheel speeds are 14 bits every 16 + ford_is_moving = 0xFCFF & (to_push->RDLR | (to_push->RDLR >> 16) | + to_push->RDHR | (to_push->RDHR >> 16)); + } + + // state machine to enter and exit controls + if ((to_push->RIR>>21) == 0x83) { + int cancel = ((to_push->RDLR >> 8) & 0x1); + int set_or_resume = (to_push->RDLR >> 28) & 0x3; + if (cancel) { + controls_allowed = 0; + } else if (set_or_resume) { + controls_allowed = 1; + } + } + + // exit controls on rising edge of brake press or on brake press when + // speed > 0 + if ((to_push->RIR>>21) == 0x165) { + int brake = to_push->RDLR & 0x20; + if (brake && (!(ford_brake_prev) || ford_is_moving)) { + controls_allowed = 0; + } + ford_brake_prev = brake; + } + + // exit controls on rising edge of gas press + if ((to_push->RIR>>21) == 0x204) { + int gas = to_push->RDLR & 0xFF03; + if (gas && !(ford_gas_prev)) { + controls_allowed = 0; + } + ford_gas_prev = gas; + } +} + +// all commands: just steering +// if controls_allowed and no pedals pressed +// allow all commands up to limit +// else +// block all commands that produce actuation + +static int ford_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // disallow actuator commands if gas or brake (with vehicle moving) are pressed + // and the the latching controls_allowed flag is True + int pedal_pressed = ford_gas_prev || (ford_brake_prev && ford_is_moving); + int current_controls_allowed = controls_allowed && !(pedal_pressed); + + // STEER: safety check + if ((to_send->RIR>>21) == 0x3CA) { + if (current_controls_allowed) { + // all messages are fine here + } else { + // bits 7-4 need to be 0xF to disallow lkas commands + if (((to_send->RDLR >> 4) & 0xF) != 0xF) return 0; + } + } + + // FORCE CANCEL: safety check only relevant when spamming the cancel button + // ensuring that set and resume aren't sent + if ((to_send->RIR>>21) == 0x83) { + if ((to_send->RDLR >> 28) & 0x3) return 0; + } + + // 1 allows the message through + return true; +} + +const safety_hooks ford_hooks = { + .init = nooutput_init, + .rx = ford_rx_hook, + .tx = ford_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = nooutput_fwd_hook, +}; diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h new file mode 100644 index 00000000000000..f35b26b4ef84d3 --- /dev/null +++ b/panda/board/safety/safety_gm.h @@ -0,0 +1,245 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// regen paddle +// accel rising edge +// brake rising edge +// brake > 0mph + +const int GM_MAX_STEER = 300; +const int GM_MAX_RT_DELTA = 128; // max delta torque allowed for real time checks +const int32_t GM_RT_INTERVAL = 250000; // 250ms between real time checks +const int GM_MAX_RATE_UP = 7; +const int GM_MAX_RATE_DOWN = 17; +const int GM_DRIVER_TORQUE_ALLOWANCE = 50; +const int GM_DRIVER_TORQUE_FACTOR = 4; +const int GM_MAX_GAS = 3072; +const int GM_MAX_REGEN = 1404; +const int GM_MAX_BRAKE = 350; + +int gm_brake_prev = 0; +int gm_gas_prev = 0; +int gm_speed = 0; +// silence everything if stock car control ECUs are still online +int gm_ascm_detected = 0; +int gm_ignition_started = 0; +int gm_rt_torque_last = 0; +int gm_desired_torque_last = 0; +uint32_t gm_ts_last = 0; +struct sample_t gm_torque_driver; // last few driver torques measured + +static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } else { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 388) { + int torque_driver_new = (((to_push->RDHR >> 16) & 0x7) << 8) | ((to_push->RDHR >> 24) & 0xFF); + torque_driver_new = to_signed(torque_driver_new, 11); + // update array of samples + update_sample(&gm_torque_driver, torque_driver_new); + } + + if (addr == 0x1f1 && bus_number == 0) { + //Bit 5 should be ignition "on" + //Backup plan is Bit 2 (accessory power) + uint32_t ign = (to_push->RDLR) & 0x20; + gm_ignition_started = ign > 0; + } + + // sample speed, really only care if car is moving or not + // rear left wheel speed + if (addr == 842) { + gm_speed = to_push->RDLR & 0xFFFF; + } + + // Check if ASCM or LKA camera are online + // on powertrain bus. + // 384 = ASCMLKASteeringCmd + // 715 = ASCMGasRegenCmd + if (bus_number == 0 && (addr == 384 || addr == 715)) { + gm_ascm_detected = 1; + controls_allowed = 0; + } + + // ACC steering wheel buttons + if (addr == 481) { + int buttons = (to_push->RDHR >> 12) & 0x7; + // res/set - enable, cancel button - disable + if (buttons == 2 || buttons == 3) { + controls_allowed = 1; + } else if (buttons == 6) { + controls_allowed = 0; + } + } + + // exit controls on rising edge of brake press or on brake press when + // speed > 0 + if (addr == 241) { + int brake = (to_push->RDLR & 0xFF00) >> 8; + // Brake pedal's potentiometer returns near-zero reading + // even when pedal is not pressed + if (brake < 10) { + brake = 0; + } + if (brake && (!gm_brake_prev || gm_speed)) { + controls_allowed = 0; + } + gm_brake_prev = brake; + } + + // exit controls on rising edge of gas press + if (addr == 417) { + int gas = to_push->RDHR & 0xFF0000; + if (gas && !gm_gas_prev) { + controls_allowed = 0; + } + gm_gas_prev = gas; + } + + // exit controls on regen paddle + if (addr == 189) { + int regen = to_push->RDLR & 0x20; + if (regen) { + controls_allowed = 0; + } + } +} + +// 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 gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // There can be only one! (ASCM) + if (gm_ascm_detected) { + return 0; + } + + // disallow actuator commands if gas or brake (with vehicle moving) are pressed + // and the the latching controls_allowed flag is True + int pedal_pressed = gm_gas_prev || (gm_brake_prev && gm_speed); + int current_controls_allowed = controls_allowed && !pedal_pressed; + + uint32_t addr; + if (to_send->RIR & 4) { + // Extended + addr = to_send->RIR >> 3; + } else { + // Normal + addr = to_send->RIR >> 21; + } + + // BRAKE: safety check + if (addr == 789) { + int rdlr = to_send->RDLR; + int brake = ((rdlr & 0xF) << 8) + ((rdlr & 0xFF00) >> 8); + brake = (0x1000 - brake) & 0xFFF; + if (current_controls_allowed) { + if (brake > GM_MAX_BRAKE) return 0; + } else { + if (brake != 0) return 0; + } + } + + // LKA STEER: safety check + if (addr == 384) { + int rdlr = to_send->RDLR; + int desired_torque = ((rdlr & 0x7) << 8) + ((rdlr & 0xFF00) >> 8); + uint32_t ts = TIM2->CNT; + int violation = 0; + desired_torque = to_signed(desired_torque, 11); + + if (current_controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, GM_MAX_STEER, -GM_MAX_STEER); + + // *** torque rate limit check *** + violation |= driver_limit_check(desired_torque, gm_desired_torque_last, &gm_torque_driver, + GM_MAX_STEER, GM_MAX_RATE_UP, GM_MAX_RATE_DOWN, + GM_DRIVER_TORQUE_ALLOWANCE, GM_DRIVER_TORQUE_FACTOR); + + // used next time + gm_desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, gm_rt_torque_last, GM_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, gm_ts_last); + if (ts_elapsed > GM_RT_INTERVAL) { + gm_rt_torque_last = desired_torque; + gm_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!current_controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !current_controls_allowed) { + gm_desired_torque_last = 0; + gm_rt_torque_last = 0; + gm_ts_last = ts; + } + + if (violation) { + return false; + } + } + + // PARK ASSIST STEER: unlimited torque, no thanks + if (addr == 823) return 0; + + // GAS/REGEN: safety check + if (addr == 715) { + int rdlr = to_send->RDLR; + int gas_regen = ((rdlr & 0x7F0000) >> 11) + ((rdlr & 0xF8000000) >> 27); + int apply = rdlr & 1; + if (current_controls_allowed) { + if (gas_regen > GM_MAX_GAS) return 0; + } else { + // Disabled message is !engaed with gas + // value that corresponds to max regen. + if (apply || gas_regen != GM_MAX_REGEN) return 0; + } + } + + // 1 allows the message through + return true; +} + +static void gm_init(int16_t param) { + controls_allowed = 0; + gm_ignition_started = 0; +} + +static int gm_ign_hook() { + return gm_ignition_started; +} + +const safety_hooks gm_hooks = { + .init = gm_init, + .rx = gm_rx_hook, + .tx = gm_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = gm_ign_hook, + .fwd = nooutput_fwd_hook, +}; + diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h index 55ef003e5fee1e..fbee6cfe861f53 100644 --- a/panda/board/safety/safety_honda.h +++ b/panda/board/safety/safety_honda.h @@ -8,11 +8,15 @@ // brake > 0mph // these are set in the Honda safety hooks...this is the wrong place +const int gas_interceptor_threshold = 328; int gas_interceptor_detected = 0; int brake_prev = 0; int gas_prev = 0; int gas_interceptor_prev = 0; int ego_speed = 0; +// TODO: auto-detect bosch hardware based on CAN messages? +bool bosch_hardware = false; +bool honda_alt_brake_msg = false; static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { @@ -33,22 +37,31 @@ static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { } } + // user brake signal on 0x17C reports applied brake from computer brake on accord + // and crv, which prevents the usual brake safety from working correctly. these + // cars have a signal on 0x1BE which only detects user's brake being applied so + // in these cases, this is used instead. + // most hondas: 0x17C bit 53 + // accord, crv: 0x1BE bit 4 + #define IS_USER_BRAKE_MSG(to_push) (!honda_alt_brake_msg ? to_push->RIR>>21 == 0x17C : to_push->RIR>>21 == 0x1BE) + #define USER_BRAKE_VALUE(to_push) (!honda_alt_brake_msg ? to_push->RDHR & 0x200000 : to_push->RDLR & 0x10) // exit controls on rising edge of brake press or on brake press when // speed > 0 - if ((to_push->RIR>>21) == 0x17C) { - // bit 53 - int brake = to_push->RDHR & 0x200000; + if (IS_USER_BRAKE_MSG(to_push)) { + int brake = USER_BRAKE_VALUE(to_push); if (brake && (!(brake_prev) || ego_speed)) { controls_allowed = 0; } brake_prev = brake; } - // exit controls on rising edge of gas press if interceptor - if ((to_push->RIR>>21) == 0x201) { + // exit controls on rising edge of gas press if interceptor (0x201 w/ len = 6) + // length check because bosch hardware also uses this id (0x201 w/ len = 8) + if ((to_push->RIR>>21) == 0x201 && (to_push->RDTR & 0xf) == 6) { gas_interceptor_detected = 1; int gas_interceptor = ((to_push->RDLR & 0xFF) << 8) | ((to_push->RDLR & 0xFF00) >> 8); - if ((gas_interceptor > 328) && (gas_interceptor_prev <= 328)) { + if ((gas_interceptor > gas_interceptor_threshold) && + (gas_interceptor_prev <= gas_interceptor_threshold)) { controls_allowed = 0; } gas_interceptor_prev = gas_interceptor; @@ -76,7 +89,8 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // disallow actuator commands if gas or brake (with vehicle moving) are pressed // and the the latching controls_allowed flag is True - int pedal_pressed = gas_prev || gas_interceptor_prev || (brake_prev && ego_speed); + int pedal_pressed = gas_prev || (gas_interceptor_prev > gas_interceptor_threshold) || + (brake_prev && ego_speed); int current_controls_allowed = controls_allowed && !(pedal_pressed); // BRAKE: safety check @@ -106,23 +120,69 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { } } + // FORCE CANCEL: safety check only relevant when spamming the cancel button in Bosch HW + // ensuring that only the cancel button press is sent (VAL 2) when controls are off. + // This avoids unintended engagements while still allowing resume spam + if (((to_send->RIR>>21) == 0x296) && bosch_hardware && + !current_controls_allowed && ((to_send->RDTR >> 4) & 0xFF) == 0) { + if (((to_send->RDLR >> 5) & 0x7) != 2) return 0; + } + // 1 allows the message through return true; } -static int honda_tx_lin_hook(int lin_num, uint8_t *data, int len) { - // TODO: add safety if using LIN - return true; +static void honda_init(int16_t param) { + controls_allowed = 0; + bosch_hardware = false; + honda_alt_brake_msg = false; } -static void honda_init() { +static void honda_bosch_init(int16_t param) { controls_allowed = 0; + bosch_hardware = true; + // Checking for alternate brake override from safety parameter + honda_alt_brake_msg = param == 1 ? true : false; +} + +static int honda_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + // fwd from car to camera. also fwd certain msgs from camera to car + // 0xE4 is steering on all cars except CRV and RDX, 0x194 for CRV and RDX, + // 0x1FA is brake control, 0x30C is acc hud, 0x33D is lkas hud, + // 0x39f is radar hud + int addr = to_fwd->RIR>>21; + if (bus_num == 0) { + return 2; + } else if (bus_num == 2 && addr != 0xE4 && addr != 0x194 && addr != 0x1FA && + addr != 0x30C && addr != 0x33D && addr != 0x39F) { + return 0; + } + + return -1; +} + +static int honda_bosch_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + if (bus_num == 1 || bus_num == 2) { + int addr = to_fwd->RIR>>21; + return addr != 0xE4 && addr != 0x33D ? (uint8_t)(~bus_num & 0x3) : -1; + } + return -1; } const safety_hooks honda_hooks = { .init = honda_init, .rx = honda_rx_hook, .tx = honda_tx_hook, - .tx_lin = honda_tx_lin_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = honda_fwd_hook, }; +const safety_hooks honda_bosch_hooks = { + .init = honda_bosch_init, + .rx = honda_rx_hook, + .tx = honda_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = honda_bosch_fwd_hook, +}; diff --git a/panda/board/safety/safety_hyundai.h b/panda/board/safety/safety_hyundai.h new file mode 100644 index 00000000000000..caac727303716e --- /dev/null +++ b/panda/board/safety/safety_hyundai.h @@ -0,0 +1,164 @@ +const int HYUNDAI_MAX_STEER = 250; +const int HYUNDAI_MAX_RT_DELTA = 112; // max delta torque allowed for real time checks +const int32_t HYUNDAI_RT_INTERVAL = 250000; // 250ms between real time checks +const int HYUNDAI_MAX_RATE_UP = 3; +const int HYUNDAI_MAX_RATE_DOWN = 7; +const int HYUNDAI_DRIVER_TORQUE_ALLOWANCE = 50; +const int HYUNDAI_DRIVER_TORQUE_FACTOR = 2; + +int hyundai_camera_detected = 0; +int hyundai_camera_bus = 0; +int hyundai_giraffe_switch_2 = 0; // is giraffe switch 2 high? +int hyundai_rt_torque_last = 0; +int hyundai_desired_torque_last = 0; +int hyundai_cruise_engaged_last = 0; +uint32_t hyundai_ts_last = 0; +struct sample_t hyundai_torque_driver; // last few driver torques measured + +static void hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } else { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 897) { + int torque_driver_new = ((to_push->RDLR >> 11) & 0xfff) - 2048; + // update array of samples + update_sample(&hyundai_torque_driver, torque_driver_new); + } + + // check if stock camera ECU is still online + if (bus == 0 && addr == 832) { + hyundai_camera_detected = 1; + controls_allowed = 0; + } + + // Find out which bus the camera is on + if (addr == 832) { + hyundai_camera_bus = bus; + } + + // enter controls on rising edge of ACC, exit controls on ACC off + if ((to_push->RIR>>21) == 1057) { + // 2 bits: 13-14 + int cruise_engaged = (to_push->RDLR >> 13) & 0x3; + if (cruise_engaged && !hyundai_cruise_engaged_last) { + controls_allowed = 1; + } else if (!cruise_engaged) { + controls_allowed = 0; + } + hyundai_cruise_engaged_last = cruise_engaged; + } + + // 832 is lkas cmd. If it is on camera bus, then giraffe switch 2 is high + if ((to_push->RIR>>21) == 832 && (bus == hyundai_camera_bus) && (hyundai_camera_bus != 0)) { + hyundai_giraffe_switch_2 = 1; + } +} + +static int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // There can be only one! (camera) + if (hyundai_camera_detected) { + return 0; + } + + uint32_t addr; + if (to_send->RIR & 4) { + // Extended + addr = to_send->RIR >> 3; + } else { + // Normal + addr = to_send->RIR >> 21; + } + + // LKA STEER: safety check + if (addr == 832) { + int desired_torque = ((to_send->RDLR >> 16) & 0x7ff) - 1024; + uint32_t ts = TIM2->CNT; + int violation = 0; + + if (controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, HYUNDAI_MAX_STEER, -HYUNDAI_MAX_STEER); + + // *** torque rate limit check *** + violation |= driver_limit_check(desired_torque, hyundai_desired_torque_last, &hyundai_torque_driver, + HYUNDAI_MAX_STEER, HYUNDAI_MAX_RATE_UP, HYUNDAI_MAX_RATE_DOWN, + HYUNDAI_DRIVER_TORQUE_ALLOWANCE, HYUNDAI_DRIVER_TORQUE_FACTOR); + + // used next time + hyundai_desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, hyundai_rt_torque_last, HYUNDAI_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, hyundai_ts_last); + if (ts_elapsed > HYUNDAI_RT_INTERVAL) { + hyundai_rt_torque_last = desired_torque; + hyundai_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + hyundai_desired_torque_last = 0; + hyundai_rt_torque_last = 0; + hyundai_ts_last = ts; + } + + if (violation) { + return false; + } + } + + // FORCE CANCEL: safety check only relevant when spamming the cancel button. + // ensuring that only the cancel button press is sent (VAL 4) when controls are off. + // This avoids unintended engagements while still allowing resume spam + // TODO: fix bug preventing the button msg to be fwd'd on bus 2 + //if (((to_send->RIR>>21) == 1265) && !controls_allowed && ((to_send->RDTR >> 4) & 0xFF) == 0) { + // if ((to_send->RDLR & 0x7) != 4) return 0; + //} + + // 1 allows the message through + return true; +} + +static int hyundai_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + // forward cam to ccan and viceversa, except lkas cmd + if ((bus_num == 0 || bus_num == hyundai_camera_bus) && hyundai_giraffe_switch_2) { + + if ((to_fwd->RIR>>21) == 832 && bus_num == hyundai_camera_bus) return -1; + if (bus_num == 0) return hyundai_camera_bus; + if (bus_num == hyundai_camera_bus) return 0; + } + return -1; +} + +static void hyundai_init(int16_t param) { + controls_allowed = 0; + hyundai_giraffe_switch_2 = 0; +} + +const safety_hooks hyundai_hooks = { + .init = hyundai_init, + .rx = hyundai_rx_hook, + .tx = hyundai_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = hyundai_fwd_hook, +}; diff --git a/panda/board/safety/safety_tesla.h b/panda/board/safety/safety_tesla.h new file mode 100644 index 00000000000000..a13e78f5a561c2 --- /dev/null +++ b/panda/board/safety/safety_tesla.h @@ -0,0 +1,287 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// regen paddle +// accel rising edge +// brake rising edge +// brake > 0mph +// +int fmax_limit_check(float val, const float MAX, const float MIN) { + return (val > MAX) || (val < MIN); +} + +// 2m/s are added to be less restrictive +const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_UP = { + {2., 7., 17.}, + {5., .8, .25}}; + +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_RT_INTERVAL = 250000; // 250ms between real time checks + +// 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_brake_prev = 0; +int tesla_gas_prev = 0; +int tesla_speed = 0; +int eac_status = 0; + +int tesla_ignition_started = 0; + + +void set_gmlan_digital_output(int to_set); +void reset_gmlan_switch_timeout(void); +void gmlan_switch_init(int timeout_enable); + + +static void 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 + + //int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) + { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } + else + { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 0x45) + { + // 6 bits starting at position 0 + int lever_position = (to_push->RDLR & 0x3F); + if (lever_position == 2) + { // pull forward + // activate openpilot + controls_allowed = 1; + //} + } + else if (lever_position == 1) + { // push towards the back + // deactivate openpilot + controls_allowed = 0; + } + } + + // Detect drive rail on (ignition) (start recording) + if (addr == 0x348) + { + // GTW_status + int drive_rail_on = (to_push->RDLR & 0x0001); + tesla_ignition_started = drive_rail_on == 1; + } + + // exit controls on brake press + // DI_torque2::DI_brakePedal 0x118 + if (addr == 0x118) + { + // 1 bit at position 16 + if (((to_push->RDLR & 0x8000)) >> 15 == 1) + { + //disable break cancel by commenting line below + controls_allowed = 0; + } + //get vehicle speed in m/s. Tesla gives MPH + tesla_speed = ((((((to_push->RDLR >> 24) & 0x0F) << 8) + ((to_push->RDLR >> 16) & 0xFF)) * 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 = ((to_push->RDHR >> 21)) & 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 == 1) && (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)((((to_push->RDLR & 0x3F) << 8) + ((to_push->RDLR >> 8) & 0xFF)) * 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; + } +} + +// 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) +{ + + uint32_t addr; + float angle_raw; + float desired_angle; + + addr = to_send->RIR >> 21; + + // do not transmit CAN message if steering angle too high + // DAS_steeringControl::DAS_steeringAngleRequest + if (addr == 0x488) + { + angle_raw = ((to_send->RDLR & 0x7F) << 8) + ((to_send->RDLR & 0xFF00) >> 8); + desired_angle = angle_raw * 0.1 - 1638.35; + int16_t violation = 0; + int st_enabled = (to_send->RDLR & 0x400000) >> 22; + + if (st_enabled == 0) { + //steering is not enabled, do not check angles and do send + tesla_desired_angle_last = desired_angle; + return true; + } + + 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.; + + //check for max angles + violation |= fmax_limit_check(desired_angle, TESLA_MAX_ANGLE, -TESLA_MAX_ANGLE); + + //check for angle delta changes + violation |= fmax_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + + if (violation) + { + controls_allowed = 0; + return false; + } + tesla_desired_angle_last = desired_angle; + return true; + } + return false; + } + return true; +} + +static int tesla_tx_lin_hook(int lin_num, uint8_t *data, int len) +{ + // LIN is not used on the Tesla + return false; +} + +static void tesla_init(int16_t param) +{ + controls_allowed = 0; + tesla_ignition_started = 0; + gmlan_switch_init(1); //init the gmlan switch with 1s timeout enabled +} + +static int tesla_ign_hook() +{ + return tesla_ignition_started; +} + +static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) +{ + + int32_t addr = to_fwd->RIR >> 21; + + if (bus_num == 0) + { + + // change inhibit of GTW_epasControl + if (addr == 0x101) + { + to_fwd->RDLR = to_fwd->RDLR | 0x4000; // 0x4000: WITH_ANGLE, 0xC000: WITH_BOTH (angle and torque) + int checksum = (((to_fwd->RDLR & 0xFF00) >> 8) + (to_fwd->RDLR & 0xFF) + 2) & 0xFF; + to_fwd->RDLR = to_fwd->RDLR & 0xFFFF; + to_fwd->RDLR = to_fwd->RDLR + (checksum << 16); + return 2; + } + + // remove EPB_epasControl + if (addr == 0x214) + { + return false; + } + + return 2; // Custom EPAS bus + } + if (bus_num == 2) + { + + // remove GTW_epasControl in forwards + if (addr == 0x101) + { + return false; + } + + return 0; // Chassis CAN + } + return false; +} + +const safety_hooks tesla_hooks = { + .init = tesla_init, + .rx = tesla_rx_hook, + .tx = tesla_tx_hook, + .tx_lin = tesla_tx_lin_hook, + .ignition = tesla_ign_hook, + .fwd = tesla_fwd_hook, +}; diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h index 0dab4b91cb9564..9cab1512f167cb 100644 --- a/panda/board/safety/safety_toyota.h +++ b/panda/board/safety/safety_toyota.h @@ -1,63 +1,73 @@ -// track the torque measured for limiting -int16_t torque_meas[3] = {0, 0, 0}; // last 3 motor torques produced by the eps -int16_t torque_meas_min = 0, torque_meas_max = 0; +int toyota_giraffe_switch_1 = 0; // is giraffe switch 1 high? +int toyota_camera_forwarded = 0; // should we forward the camera bus? // global torque limit -const int32_t MAX_TORQUE = 1500; // max torque cmd allowed ever +const int TOYOTA_MAX_TORQUE = 1500; // max torque cmd allowed ever // rate based torque limit + stay within actually applied // packet is sent at 100hz, so this limit is 1000/sec -const int32_t MAX_RATE_UP = 10; // ramp up slow -const int32_t MAX_RATE_DOWN = 25; // ramp down fast -const int32_t MAX_TORQUE_ERROR = 500; // max torque cmd in excess of torque motor +const int TOYOTA_MAX_RATE_UP = 10; // ramp up slow +const int TOYOTA_MAX_RATE_DOWN = 25; // ramp down fast +const int TOYOTA_MAX_TORQUE_ERROR = 350; // max torque cmd in excess of torque motor // real time torque limit to prevent controls spamming // the real time limit is 1500/sec -const int32_t MAX_RT_DELTA = 375; // max delta torque allowed for real time checks -const int32_t RT_INTERVAL = 250000; // 250ms between real time checks +const int TOYOTA_MAX_RT_DELTA = 375; // max delta torque allowed for real time checks +const int TOYOTA_RT_INTERVAL = 250000; // 250ms between real time checks // longitudinal limits -const int16_t MAX_ACCEL = 1500; // 1.5 m/s2 -const int16_t MIN_ACCEL = -3000; // 3.0 m/s2 +const int TOYOTA_MAX_ACCEL = 1500; // 1.5 m/s2 +const int TOYOTA_MIN_ACCEL = -3000; // 3.0 m/s2 // global actuation limit state -int actuation_limits = 1; // by default steer limits are imposed +int toyota_actuation_limits = 1; // by default steer limits are imposed +int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file // state of torque limits -int16_t desired_torque_last = 0; // last desired steer torque -int16_t rt_torque_last = 0; // last desired torque for real time check -uint32_t ts_last = 0; +int toyota_desired_torque_last = 0; // last desired steer torque +int toyota_rt_torque_last = 0; // last desired torque for real time check +uint32_t toyota_ts_last = 0; +int toyota_cruise_engaged_last = 0; // cruise state +struct sample_t toyota_torque_meas; // last 3 motor torques produced by the eps + static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { // get eps motor torque (0.66 factor in dbc) if ((to_push->RIR>>21) == 0x260) { - int16_t torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF)); + int torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF)); + torque_meas_new = to_signed(torque_meas_new, 16); - // increase torque_meas by 1 to be conservative on rounding - torque_meas_new = (torque_meas_new / 3 + (torque_meas_new > 0 ? 1 : -1)) * 2; + // scale by dbc_factor + torque_meas_new = (torque_meas_new * toyota_dbc_eps_torque_factor) / 100; - // shift the array - for (int i = sizeof(torque_meas)/sizeof(torque_meas[0]) - 1; i > 0; i--) { - torque_meas[i] = torque_meas[i-1]; - } - torque_meas[0] = torque_meas_new; + // increase torque_meas by 1 to be conservative on rounding + torque_meas_new += (torque_meas_new > 0 ? 1 : -1); - // get the minimum and maximum measured torque over the last 3 frames - torque_meas_min = torque_meas_max = torque_meas[0]; - for (int i = 1; i < sizeof(torque_meas)/sizeof(torque_meas[0]); i++) { - if (torque_meas[i] < torque_meas_min) torque_meas_min = torque_meas[i]; - if (torque_meas[i] > torque_meas_max) torque_meas_max = torque_meas[i]; - } + // update array of sample + update_sample(&toyota_torque_meas, torque_meas_new); } - // exit controls on ACC off + // enter controls on rising edge of ACC, exit controls on ACC off if ((to_push->RIR>>21) == 0x1D2) { - // 4 bits: 55-52 - if (to_push->RDHR & 0xF00000) { + // 5th bit is CRUISE_ACTIVE + int cruise_engaged = to_push->RDLR & 0x20; + if (cruise_engaged && !toyota_cruise_engaged_last) { controls_allowed = 1; - } else { + } else if (!cruise_engaged) { controls_allowed = 0; } + toyota_cruise_engaged_last = cruise_engaged; + } + + int bus = (to_push->RDTR >> 4) & 0xF; + // msgs are only on bus 2 if panda is connected to frc + if (bus == 2) { + toyota_camera_forwarded = 1; + } + + // 0x2E4 is lkas cmd. If it is on bus 0, then giraffe switch 1 is high + if ((to_push->RIR>>21) == 0x2E4 && (bus == 0)) { + toyota_giraffe_switch_1 = 1; } } @@ -66,13 +76,16 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // Check if msg is sent on BUS 0 if (((to_send->RDTR >> 4) & 0xF) == 0) { + // no IPAS in non IPAS mode + if (((to_send->RIR>>21) == 0x266) || ((to_send->RIR>>21) == 0x167)) return false; + // ACCEL: safety check on byte 1-2 if ((to_send->RIR>>21) == 0x343) { - int16_t desired_accel = ((to_send->RDLR & 0xFF) << 8) | ((to_send->RDLR >> 8) & 0xFF); - if (controls_allowed && actuation_limits) { - if ((desired_accel > MAX_ACCEL) || (desired_accel < MIN_ACCEL)) { - return 0; - } + int desired_accel = ((to_send->RDLR & 0xFF) << 8) | ((to_send->RDLR >> 8) & 0xFF); + desired_accel = to_signed(desired_accel, 16); + if (controls_allowed && toyota_actuation_limits) { + int violation = max_limit_check(desired_accel, TOYOTA_MAX_ACCEL, TOYOTA_MIN_ACCEL); + if (violation) return 0; } else if (!controls_allowed && (desired_accel != 0)) { return 0; } @@ -80,53 +93,36 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // STEER: safety check on bytes 2-3 if ((to_send->RIR>>21) == 0x2E4) { - int16_t desired_torque = (to_send->RDLR & 0xFF00) | ((to_send->RDLR >> 16) & 0xFF); - int16_t violation = 0; + int desired_torque = (to_send->RDLR & 0xFF00) | ((to_send->RDLR >> 16) & 0xFF); + desired_torque = to_signed(desired_torque, 16); + int violation = 0; uint32_t ts = TIM2->CNT; // only check if controls are allowed and actuation_limits are imposed - if (controls_allowed && actuation_limits) { + if (controls_allowed && toyota_actuation_limits) { // *** global torque limit check *** - if (desired_torque < -MAX_TORQUE) violation = 1; - if (desired_torque > MAX_TORQUE) violation = 1; - + violation |= max_limit_check(desired_torque, TOYOTA_MAX_TORQUE, -TOYOTA_MAX_TORQUE); // *** torque rate limit check *** - int16_t highest_allowed_torque = max(desired_torque_last, 0) + MAX_RATE_UP; - int16_t lowest_allowed_torque = min(desired_torque_last, 0) - MAX_RATE_UP; - - // if we've exceeded the applied torque, we must start moving toward 0 - highest_allowed_torque = min(highest_allowed_torque, max(desired_torque_last - MAX_RATE_DOWN, max(torque_meas_max, 0) + MAX_TORQUE_ERROR)); - lowest_allowed_torque = max(lowest_allowed_torque, min(desired_torque_last + MAX_RATE_DOWN, min(torque_meas_min, 0) - MAX_TORQUE_ERROR)); - - // check for violation - if ((desired_torque < lowest_allowed_torque) || (desired_torque > highest_allowed_torque)) { - violation = 1; - } + violation |= dist_to_meas_check(desired_torque, toyota_desired_torque_last, + &toyota_torque_meas, TOYOTA_MAX_RATE_UP, TOYOTA_MAX_RATE_DOWN, TOYOTA_MAX_TORQUE_ERROR); // used next time - desired_torque_last = desired_torque; - + toyota_desired_torque_last = desired_torque; // *** torque real time rate limit check *** - int16_t highest_rt_torque = max(rt_torque_last, 0) + MAX_RT_DELTA; - int16_t lowest_rt_torque = min(rt_torque_last, 0) - MAX_RT_DELTA; - - // check for violation - if ((desired_torque < lowest_rt_torque) || (desired_torque > highest_rt_torque)) { - violation = 1; - } + violation |= rt_rate_limit_check(desired_torque, toyota_rt_torque_last, TOYOTA_MAX_RT_DELTA); // every RT_INTERVAL set the new limits - uint32_t ts_elapsed = ts > ts_last ? ts - ts_last : (0xFFFFFFFF - ts_last) + 1 + ts; - if (ts_elapsed > RT_INTERVAL) { - rt_torque_last = desired_torque; - ts_last = ts; + uint32_t ts_elapsed = get_ts_elapsed(ts, toyota_ts_last); + if (ts_elapsed > TOYOTA_RT_INTERVAL) { + toyota_rt_torque_last = desired_torque; + toyota_ts_last = ts; } } - + // no torque if controls is not allowed if (!controls_allowed && (desired_torque != 0)) { violation = 1; @@ -134,9 +130,9 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // reset to 0 if either controls is not allowed or there's a violation if (violation || !controls_allowed) { - desired_torque_last = 0; - rt_torque_last = 0; - ts_last = ts; + toyota_desired_torque_last = 0; + toyota_rt_torque_last = 0; + toyota_ts_last = ts; } if (violation) { @@ -149,31 +145,48 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { return true; } -static int toyota_tx_lin_hook(int lin_num, uint8_t *data, int len) { - // TODO: add safety if using LIN - return true; +static void toyota_init(int16_t param) { + controls_allowed = 0; + toyota_actuation_limits = 1; + toyota_giraffe_switch_1 = 0; + toyota_camera_forwarded = 0; + toyota_dbc_eps_torque_factor = param; } -static void toyota_init() { - controls_allowed = 0; - actuation_limits = 1; +static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + + // forward cam to radar and viceversa if car, except lkas cmd and hud + // don't forward when switch 1 is high + if ((bus_num == 0 || bus_num == 2) && toyota_camera_forwarded && !toyota_giraffe_switch_1) { + int addr = to_fwd->RIR>>21; + bool is_lkas_msg = (addr == 0x2E4 || addr == 0x412) && bus_num == 2; + return is_lkas_msg? -1 : (uint8_t)(~bus_num & 0x2); + } + return -1; } const safety_hooks toyota_hooks = { .init = toyota_init, .rx = toyota_rx_hook, .tx = toyota_tx_hook, - .tx_lin = toyota_tx_lin_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = toyota_fwd_hook, }; -static void toyota_nolimits_init() { +static void toyota_nolimits_init(int16_t param) { controls_allowed = 0; - actuation_limits = 0; + toyota_actuation_limits = 0; + toyota_giraffe_switch_1 = 0; + toyota_camera_forwarded = 0; + toyota_dbc_eps_torque_factor = param; } const safety_hooks toyota_nolimits_hooks = { .init = toyota_nolimits_init, .rx = toyota_rx_hook, .tx = toyota_tx_hook, - .tx_lin = toyota_tx_lin_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = toyota_fwd_hook, }; diff --git a/panda/board/safety/safety_toyota_ipas.h b/panda/board/safety/safety_toyota_ipas.h new file mode 100644 index 00000000000000..ff4158e3c77c3b --- /dev/null +++ b/panda/board/safety/safety_toyota_ipas.h @@ -0,0 +1,156 @@ +// uses tons from safety_toyota +// TODO: refactor to repeat less code + +// IPAS override +const int32_t TOYOTA_IPAS_OVERRIDE_THRESHOLD = 200; // disallow controls when user torque exceeds this value + +// 2m/s are added to be less restrictive +const struct lookup_t LOOKUP_ANGLE_RATE_UP = { + {2., 7., 17.}, + {5., .8, .15}}; + +const struct lookup_t LOOKUP_ANGLE_RATE_DOWN = { + {2., 7., 17.}, + {5., 3.5, .4}}; + +const float RT_ANGLE_FUDGE = 1.5; // for RT checks allow 50% more angle change +const float CAN_TO_DEG = 2. / 3.; // convert angles from CAN unit to degrees + +int ipas_state = 1; // 1 disabled, 3 executing angle control, 5 override +int angle_control = 0; // 1 if direct angle control packets are seen +float speed = 0.; + +struct sample_t angle_meas; // last 3 steer angles +struct sample_t torque_driver; // last 3 driver steering torque + +// state of angle limits +int16_t desired_angle_last = 0; // last desired steer angle +int16_t rt_angle_last = 0; // last desired torque for real time check +uint32_t ts_angle_last = 0; + +int controls_allowed_last = 0; + + +static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + // check standard toyota stuff as well + toyota_rx_hook(to_push); + + if ((to_push->RIR>>21) == 0x260) { + // get driver steering torque + int16_t torque_driver_new = (((to_push->RDLR) & 0xFF00) | ((to_push->RDLR >> 16) & 0xFF)); + + // update array of samples + update_sample(&torque_driver, torque_driver_new); + } + + // get steer angle + if ((to_push->RIR>>21) == 0x25) { + int angle_meas_new = ((to_push->RDLR & 0xf) << 8) + ((to_push->RDLR & 0xff00) >> 8); + uint32_t ts = TIM2->CNT; + + angle_meas_new = to_signed(angle_meas_new, 12); + + // update array of samples + update_sample(&angle_meas, angle_meas_new); + + // *** angle real time check + // add 1 to not false trigger the violation and multiply by 20 since the check is done every 250ms and steer angle is updated at 80Hz + int rt_delta_angle_up = ((int)(RT_ANGLE_FUDGE * (interpolate(LOOKUP_ANGLE_RATE_UP, speed) * 20. * CAN_TO_DEG + 1.))); + int rt_delta_angle_down = ((int)(RT_ANGLE_FUDGE * (interpolate(LOOKUP_ANGLE_RATE_DOWN, speed) * 20. * CAN_TO_DEG + 1.))); + int highest_rt_angle = rt_angle_last + (rt_angle_last > 0? rt_delta_angle_up:rt_delta_angle_down); + int lowest_rt_angle = rt_angle_last - (rt_angle_last > 0? rt_delta_angle_down:rt_delta_angle_up); + + // every RT_INTERVAL or when controls are turned on, set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, ts_angle_last); + if ((ts_elapsed > TOYOTA_RT_INTERVAL) || (controls_allowed && !controls_allowed_last)) { + rt_angle_last = angle_meas_new; + ts_angle_last = ts; + } + + // check for violation + if (angle_control && + ((angle_meas_new < lowest_rt_angle) || + (angle_meas_new > highest_rt_angle))) { + controls_allowed = 0; + } + + controls_allowed_last = controls_allowed; + } + + // get speed + if ((to_push->RIR>>21) == 0xb4) { + speed = ((float) (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF))) * 0.01 / 3.6; + } + + // get ipas state + if ((to_push->RIR>>21) == 0x262) { + ipas_state = (to_push->RDLR & 0xf); + } + + // exit controls on high steering override + if (angle_control && ((torque_driver.min > TOYOTA_IPAS_OVERRIDE_THRESHOLD) || + (torque_driver.max < -TOYOTA_IPAS_OVERRIDE_THRESHOLD) || + (ipas_state==5))) { + controls_allowed = 0; + } +} + +static int toyota_ipas_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // Check if msg is sent on BUS 0 + if (((to_send->RDTR >> 4) & 0xF) == 0) { + + // STEER ANGLE + if (((to_send->RIR>>21) == 0x266) || ((to_send->RIR>>21) == 0x167)) { + + angle_control = 1; // we are in angle control mode + int desired_angle = ((to_send->RDLR & 0xf) << 8) + ((to_send->RDLR & 0xff00) >> 8); + int ipas_state_cmd = ((to_send->RDLR & 0xff) >> 4); + int16_t violation = 0; + + desired_angle = to_signed(desired_angle, 12); + + if (controls_allowed) { + // add 1 to not false trigger the violation + int delta_angle_up = (int) (interpolate(LOOKUP_ANGLE_RATE_UP, speed) * CAN_TO_DEG + 1.); + int delta_angle_down = (int) (interpolate(LOOKUP_ANGLE_RATE_DOWN, speed) * CAN_TO_DEG + 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 ((desired_angle > highest_desired_angle) || + (desired_angle < lowest_desired_angle)){ + violation = 1; + controls_allowed = 0; + } + } + + // desired steer angle should be the same as steer angle measured when controls are off + if ((!controls_allowed) && + ((desired_angle < (angle_meas.min - 1)) || + (desired_angle > (angle_meas.max + 1)) || + (ipas_state_cmd != 1))) { + violation = 1; + } + + desired_angle_last = desired_angle; + + if (violation) { + return false; + } + + return true; + } + } + + // check standard toyota stuff as well + return toyota_tx_hook(to_send); +} + +const safety_hooks toyota_ipas_hooks = { + .init = toyota_init, + .rx = toyota_ipas_rx_hook, + .tx = toyota_ipas_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = toyota_fwd_hook, +}; + diff --git a/panda/board/spi_flasher.h b/panda/board/spi_flasher.h index 5d979a09d244c8..179a095b970ef9 100644 --- a/panda/board/spi_flasher.h +++ b/panda/board/spi_flasher.h @@ -130,6 +130,120 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { return resp_len; } +#ifdef PEDAL + +#define CAN CAN1 + +#define CAN_BL_INPUT 0x1 +#define CAN_BL_OUTPUT 0x2 + +void CAN1_TX_IRQHandler() { + // clear interrupt + CAN->TSR |= CAN_TSR_RQCP0; +} + +#define ISOTP_BUF_SIZE 0x110 + +uint8_t isotp_buf[ISOTP_BUF_SIZE]; +uint8_t *isotp_buf_ptr = NULL; +int isotp_buf_remain = 0; + +uint8_t isotp_buf_out[ISOTP_BUF_SIZE]; +uint8_t *isotp_buf_out_ptr = NULL; +int isotp_buf_out_remain = 0; +int isotp_buf_out_idx = 0; + +void bl_can_send(uint8_t *odat) { + // wait for send + while (!(CAN->TSR & CAN_TSR_TME0)); + + // send continue + CAN->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0]; + CAN->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1]; + CAN->sTxMailBox[0].TDTR = 8; + CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1; +} + +void CAN1_RX0_IRQHandler() { + while (CAN->RF0R & CAN_RF0R_FMP0) { + if ((CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) { + uint8_t dat[8]; + ((uint32_t*)dat)[0] = CAN->sFIFOMailBox[0].RDLR; + ((uint32_t*)dat)[1] = CAN->sFIFOMailBox[0].RDHR; + uint8_t odat[8]; + uint8_t type = dat[0] & 0xF0; + if (type == 0x30) { + // continue + while (isotp_buf_out_remain > 0) { + // wait for send + while (!(CAN->TSR & CAN_TSR_TME0)); + + odat[0] = 0x20 | isotp_buf_out_idx; + memcpy(odat+1, isotp_buf_out_ptr, 7); + isotp_buf_out_remain -= 7; + isotp_buf_out_ptr += 7; + isotp_buf_out_idx++; + + bl_can_send(odat); + } + } else if (type == 0x20) { + if (isotp_buf_remain > 0) { + memcpy(isotp_buf_ptr, dat+1, 7); + isotp_buf_ptr += 7; + isotp_buf_remain -= 7; + } + if (isotp_buf_remain <= 0) { + int len = isotp_buf_ptr - isotp_buf + isotp_buf_remain; + + // call the function + memset(isotp_buf_out, 0, ISOTP_BUF_SIZE); + isotp_buf_out_remain = spi_cb_rx(isotp_buf, len, isotp_buf_out); + isotp_buf_out_ptr = isotp_buf_out; + isotp_buf_out_idx = 0; + + // send initial + if (isotp_buf_out_remain <= 7) { + odat[0] = isotp_buf_out_remain; + memcpy(odat+1, isotp_buf_out_ptr, isotp_buf_out_remain); + } else { + odat[0] = 0x10 | (isotp_buf_out_remain>>8); + odat[1] = isotp_buf_out_remain & 0xFF; + memcpy(odat+2, isotp_buf_out_ptr, 6); + isotp_buf_out_remain -= 6; + isotp_buf_out_ptr += 6; + isotp_buf_out_idx++; + } + + bl_can_send(odat); + } + } else if (type == 0x10) { + int len = ((dat[0]&0xF)<<8) | dat[1]; + + // setup buffer + isotp_buf_ptr = isotp_buf; + memcpy(isotp_buf_ptr, dat+2, 6); + + if (len < (ISOTP_BUF_SIZE-0x10)) { + isotp_buf_ptr += 6; + isotp_buf_remain = len-6; + } + + memset(odat, 0, 8); + odat[0] = 0x30; + bl_can_send(odat); + } + } + // next + CAN->RF0R |= CAN_RF0R_RFOM0; + } +} + +void CAN1_SCE_IRQHandler() { + can_sce(CAN); +} + +#endif + void soft_flasher_start() { puts("\n\n\n************************ FLASHER START ************************\n"); @@ -140,6 +254,20 @@ void soft_flasher_start() { RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; RCC->APB1ENR |= RCC_APB1ENR_USART2EN; +// pedal has the canloader +#ifdef PEDAL + RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; + + // B8,B9: CAN 1 + set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); + set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); + set_can_enable(CAN1, 1); + + // init can + can_silent = ALL_CAN_LIVE; + can_init(0); +#endif + // A4,A5,A6,A7: setup SPI set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); diff --git a/panda/boardesp/README.md b/panda/boardesp/README.md index 9b15ef2351e924..5a8fab14777fee 100644 --- a/panda/boardesp/README.md +++ b/panda/boardesp/README.md @@ -2,13 +2,13 @@ Dependencies ----- -**Mac** +**Debian / Ubuntu** ``` ./get_sdk.sh ``` -**Debian / Ubuntu** +**Mac** ``` ./get_sdk_mac.sh diff --git a/panda/boardesp/elm327.c b/panda/boardesp/elm327.c index 993dc8460a62fb..6c18c4463b484d 100644 --- a/panda/boardesp/elm327.c +++ b/panda/boardesp/elm327.c @@ -1157,7 +1157,7 @@ static const elm_protocol_t elm_protocols[] = { {false, NA, 104, elm_process_obd_cmd_J1850, NULL, "SAE J1850 VPW", }, {false, LIN, 104, elm_process_obd_cmd_LIN5baud, NULL, "ISO 9141-2", }, {false, LIN, 104, elm_process_obd_cmd_LIN5baud, NULL, "ISO 14230-4 (KWP 5BAUD)", }, - {true, LIN, 104, elm_process_obd_cmd_LINFast, elm_init_LINFast, "ISO 14230-4 (KWP FAST)", }, + {true, LIN, 104, elm_process_obd_cmd_LINFast, NULL, "ISO 14230-4 (KWP FAST)", }, {true, CAN11, 5000, elm_process_obd_cmd_ISO15765, elm_init_ISO15765, "ISO 15765-4 (CAN 11/500)",}, {true, CAN29, 5000, elm_process_obd_cmd_ISO15765, elm_init_ISO15765, "ISO 15765-4 (CAN 29/500)",}, {true, CAN11, 2500, elm_process_obd_cmd_ISO15765, elm_init_ISO15765, "ISO 15765-4 (CAN 11/250)",}, diff --git a/panda/boardesp/proxy.c b/panda/boardesp/proxy.c index d7feb39c33fdba..bb89743c198ec9 100644 --- a/panda/boardesp/proxy.c +++ b/panda/boardesp/proxy.c @@ -20,6 +20,9 @@ _a > _b ? _a : _b; }) char ssid[32]; +char password[] = "testing123"; +int wifi_secure_mode = 0; + static const int pin = 2; // Structure holding the TCP connection information. @@ -218,15 +221,54 @@ void ICACHE_FLASH_ATTR inter_recv_cb(void *arg, char *pusrdata, unsigned short l } } +void ICACHE_FLASH_ATTR wifi_configure(int secure) { + wifi_secure_mode = secure; + + // start wifi AP + wifi_set_opmode(SOFTAP_MODE); + struct softap_config config = {0}; + wifi_softap_get_config(&config); + strcpy(config.ssid, ssid); + if (wifi_secure_mode == 0) strcat(config.ssid, "-pair"); + strcpy(config.password, password); + config.ssid_len = strlen(config.ssid); + config.authmode = wifi_secure_mode ? AUTH_WPA2_PSK : AUTH_OPEN; + config.beacon_interval = 100; + config.max_connection = 4; + wifi_softap_set_config(&config); + + if (wifi_secure_mode) { + // setup tcp server + tcp_proto.local_port = 1337; + tcp_conn.type = ESPCONN_TCP; + tcp_conn.state = ESPCONN_NONE; + tcp_conn.proto.tcp = &tcp_proto; + espconn_regist_connectcb(&tcp_conn, tcp_connect_cb); + espconn_accept(&tcp_conn); + espconn_regist_time(&tcp_conn, 60, 0); // 60s timeout for all connections + + // setup inter server + inter_proto.local_port = 1338; + const char udp_remote_ip[4] = {255, 255, 255, 255}; + os_memcpy(inter_proto.remote_ip, udp_remote_ip, 4); + inter_proto.remote_port = 1338; + + inter_conn.type = ESPCONN_UDP; + inter_conn.proto.udp = &inter_proto; + + espconn_regist_recvcb(&inter_conn, inter_recv_cb); + espconn_create(&inter_conn); + } +} + void ICACHE_FLASH_ATTR wifi_init() { // default ssid and password memset(ssid, 0, 32); - os_sprintf(ssid, "panda-%08x-BROKEN", system_get_chip_id()); - char password[] = "testing123"; + os_sprintf(ssid, "panda-%08x-BROKEN", system_get_chip_id()); // fetch secure ssid and password - // update, try 3 times - for (int i = 0; i < 3; i++) { + // update, try 20 times, for 1 second + for (int i = 0; i < 20; i++) { uint8_t digest[SHA_DIGEST_SIZE]; char resp[0x20]; __spi_comm("\x00\x00\x00\x00\x40\xD0\x00\x00\x00\x00\x20\x00", 0xC, recvData, 0x40); @@ -241,20 +283,11 @@ void ICACHE_FLASH_ATTR wifi_init() { } os_delay_us(50000); } + os_printf("Finished getting SID\n"); + os_printf(ssid); + os_printf("\n"); - // start wifi AP - wifi_set_opmode(SOFTAP_MODE); - struct softap_config config; - wifi_softap_get_config(&config); - strcpy(config.ssid, ssid); - strcpy(config.password, password); - config.ssid_len = strlen(ssid); - config.authmode = AUTH_WPA2_PSK; - config.beacon_interval = 100; - config.max_connection = 10; - wifi_softap_set_config(&config); - - //set IP + // set IP wifi_softap_dhcps_stop(); //stop DHCP before setting static IP struct ip_info ip_config; IP4_ADDR(&ip_config.ip, 192, 168, 0, 10); @@ -265,27 +298,7 @@ void ICACHE_FLASH_ATTR wifi_init() { wifi_softap_set_dhcps_offer_option(OFFER_ROUTER, &stupid_gateway); wifi_softap_dhcps_start(); - // setup tcp server - tcp_proto.local_port = 1337; - tcp_conn.type = ESPCONN_TCP; - tcp_conn.state = ESPCONN_NONE; - tcp_conn.proto.tcp = &tcp_proto; - espconn_regist_connectcb(&tcp_conn, tcp_connect_cb); - espconn_accept(&tcp_conn); - espconn_regist_time(&tcp_conn, 60, 0); // 60s timeout for all connections - - // setup inter server - inter_proto.local_port = 1338; - const char udp_remote_ip[4] = {255, 255, 255, 255}; - os_memcpy(inter_proto.remote_ip, udp_remote_ip, 4); - inter_proto.remote_port = 1338; - - inter_conn.type = ESPCONN_UDP; - inter_conn.proto.udp = &inter_proto; - - espconn_regist_recvcb(&inter_conn, inter_recv_cb); - - espconn_create(&inter_conn); + wifi_configure(0); } #define LOOP_PRIO 2 @@ -301,7 +314,7 @@ void ICACHE_FLASH_ATTR user_init() { gpio_init(); // configure UART TXD to be GPIO1, set as output - PIN_FUNC_SELECT(PERIPHS_IO_MUX_U0TXD_U, FUNC_GPIO1); + PIN_FUNC_SELECT(PERIPHS_IO_MUX_U0TXD_U, FUNC_GPIO1); gpio_output_set(0, 0, (1 << pin), 0); // configure SPI @@ -321,7 +334,7 @@ void ICACHE_FLASH_ATTR user_init() { //SPICsPinSelect(SpiNum_HSPI, SpiPinCS_1); // configure UART TXD to be GPIO1, set as output - PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO5_U, FUNC_GPIO5); + PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO5_U, FUNC_GPIO5); gpio_output_set(0, 0, (1 << 5), 0); gpio_output_set((1 << 5), 0, 0, 0); @@ -354,7 +367,6 @@ void ICACHE_FLASH_ATTR user_init() { system_os_post(LOOP_PRIO, 0, 0); } - void ICACHE_FLASH_ATTR loop(os_event_t *events) { system_os_post(LOOP_PRIO, 0, 0); } diff --git a/panda/boardesp/webserver.c b/panda/boardesp/webserver.c index 66b1185fefd719..9266b08f70f605 100644 --- a/panda/boardesp/webserver.c +++ b/panda/boardesp/webserver.c @@ -40,6 +40,7 @@ char OK_header[] = "HTTP/1.0 200 OK\nContent-Type: text/html\n\n"; static struct espconn web_conn; static esp_tcp web_proto; extern char ssid[]; +extern int wifi_secure_mode; char *st_firmware; int real_content_length, content_length = 0; @@ -205,6 +206,12 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) { } else { ets_strcat(resp, "\nesp flash file: user1.bin"); } + + if (wifi_secure_mode) { + ets_strcat(resp, "\nin secure mode"); + } else { + ets_strcat(resp, "\nin INSECURE mode...secure it"); + } ets_strcat(resp,"\nSet USB Mode:" "" @@ -215,8 +222,9 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) { espconn_send_string(&web_conn, resp); espconn_disconnect(conn); - - } else if (memcmp(data, "GET /set_property?usb_mode=", 27) == 0) { + } else if (memcmp(data, "GET /secure", 11) == 0 && !wifi_secure_mode) { + wifi_configure(1); + } else if (memcmp(data, "GET /set_property?usb_mode=", 27) == 0 && wifi_secure_mode) { char mode_value = data[27] - '0'; if (mode_value >= '\x00' && mode_value <= '\x02') { memset(resp, 0, MAX_RESP); @@ -228,7 +236,7 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) { espconn_send_string(&web_conn, resp); espconn_disconnect(conn); } - } else if (memcmp(data, "PUT /stupdate ", 14) == 0) { + } else if (memcmp(data, "PUT /stupdate ", 14) == 0 && wifi_secure_mode) { os_printf("init st firmware\n"); char *cl = strstr(data, "Content-Length: "); if (cl != NULL) { @@ -244,8 +252,8 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) { state = RECEIVING_ST_FIRMWARE; } - } else if ((memcmp(data, "PUT /espupdate1 ", 16) == 0) || - (memcmp(data, "PUT /espupdate2 ", 16) == 0)) { + } else if (((memcmp(data, "PUT /espupdate1 ", 16) == 0) || + (memcmp(data, "PUT /espupdate2 ", 16) == 0)) && wifi_secure_mode) { // 0x1000 = user1.bin // 0x81000 = user2.bin // 0x3FE000 = blank.bin diff --git a/panda/buy.png b/panda/buy.png index 0d4f2225b0fb4a..a4a9e0fd40a426 100644 Binary files a/panda/buy.png and b/panda/buy.png differ diff --git a/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj index 9ac10e8bc1d1e0..4b9de8c442828a 100644 --- a/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj +++ b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj @@ -1,178 +1,178 @@ - - - - - Debug - Win32 - - - Release - Win32 - - - Debug - x64 - - - Release - x64 - - - - {D99E2FCD-21A4-4065-949A-31E34E0E69D1} - Win32Proj - ECUsimCLI - 8.1 - - - - Application - true - v140 - Unicode - - - Application - false - v140 - true - Unicode - - - Application - true - v140 - Unicode - - - Application - false - v140 - true - Unicode - - - - - - - - - - - - - - - - - - - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - false - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - false - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - - Use - Level3 - Disabled - WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib - - - - - Use - Level3 - Disabled - _DEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib - - - - - Level3 - Use - MaxSpeed - true - true - WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib - - - - - Level3 - Use - MaxSpeed - true - true - NDEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib - - - - - - - - - - - Create - Create - Create - Create - - - - - {96e0e646-ee76-444d-9a77-a0cd7f781deb} - - - - - + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {D99E2FCD-21A4-4065-949A-31E34E0E69D1} + Win32Proj + ECUsimCLI + 10.0.16299.0 + + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + Use + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + + + + + + + Create + Create + Create + Create + + + + + {96e0e646-ee76-444d-9a77-a0cd7f781deb} + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj b/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj index d50a0a29181fce..93d75c14be1c7a 100644 --- a/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj +++ b/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj @@ -1,197 +1,197 @@ - - - - - Debug - Win32 - - - Release - Win32 - - - Debug - x64 - - - Release - x64 - - - - {96E0E646-EE76-444D-9A77-A0CD7F781DEB} - Win32Proj - ECUsimDLL - 8.1 - - - - DynamicLibrary - true - v140 - Unicode - - - DynamicLibrary - false - v140 - true - Unicode - - - DynamicLibrary - true - v140 - Unicode - - - DynamicLibrary - false - v140 - true - Unicode - - - - - - - - - - - - - - - - - - - - - true - ecusim - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - true - ecusim - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - false - ecusim - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - false - ecusim - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - - Use - Level3 - Disabled - WIN32;_DEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Windows - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib - - - - - Use - Level3 - Disabled - _DEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Windows - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib - - - - - Level3 - Use - MaxSpeed - true - true - WIN32;NDEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Windows - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib - - - - - Level3 - Use - MaxSpeed - true - true - NDEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Windows - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib - - - - - - - - - - - false - - - false - - - false - - - false - - - - - - Create - Create - Create - Create - - - - - {5528aefb-638d-49af-b9d4-965154e7d531} - - - - - + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {96E0E646-EE76-444D-9A77-A0CD7F781DEB} + Win32Proj + ECUsimDLL + 10.0.16299.0 + + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Use + Level3 + Disabled + _DEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + + + + + + + false + + + false + + + false + + + false + + + + + + Create + Create + Create + Create + + + + + {5528aefb-638d-49af-b9d4-965154e7d531} + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/ECUsim DLL/ECUsim.h b/panda/drivers/windows/ECUsim DLL/ECUsim.h index 7378e2c5811d84..2f5fe0f7ad4865 100644 --- a/panda/drivers/windows/ECUsim DLL/ECUsim.h +++ b/panda/drivers/windows/ECUsim DLL/ECUsim.h @@ -1,7 +1,7 @@ #pragma once #include -#include "panda\panda.h" +#include "panda_shared/panda.h" #include // The following ifdef block is the standard way of creating macros which make exporting diff --git a/panda/drivers/windows/README.md b/panda/drivers/windows/README.md index 7219abda2485e5..06c7a51101914d 100644 --- a/panda/drivers/windows/README.md +++ b/panda/drivers/windows/README.md @@ -18,6 +18,35 @@ ______/\\\\\\\\\\\____/\\\\\\\\\_______/\\\\\\\\\\\\\\\______/\\\\\\\\\\________ ``` +# Installing J2534 driver: + +[Download](https://github.com/commaai/panda/files/1742802/panda.J2534.driver.install.zip) + +Depending on what version of windows you are on, you may need to separately install the WinUSB driver (see next section). + +# Installing WinUSB driver: + +Installation automatically happens for Windows 8 and Windows 10 because the panda +firmware contains the USB descriptors necessary to auto-install the WinUSB driver. + +Windows 7 will not auto-install the WinUSB driver. You can use Zadig to install +the WinUSB driver. This software is not tested on anything before 7. + +More details here: +[WinUSB (Winusb.sys) Installation](https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation) +[WCID Devices](https://github.com/pbatard/libwdi/wiki/WCID-Devices) +[Zadig for installing libusb compatible driver](https://github.com/pbatard/libwdi/wiki/Zadig) + +# Using J2534: + +After installing the J2534 drivers for the panda, you can do... nothing. +You first need to get a J2534 client that can load the drivers and talk to +the panda for you. + +A simple tool for testing J2534 drivers is DrewTech's 'J2534-1 Bus Analysis +Tool' available in the 'Other Support Applications' section of their +[Download Page](http://www.drewtech.com/downloads/). + # What is J2534? J2534 is an API that tries to provide a consistent way to send/receive @@ -56,10 +85,8 @@ features. # Building the Project: -This project was developed with Visual Studio 2015, the Windows SDK, -and the Windows Driver Kit (WDK). At the time of writing, there is not -a stable WDK for Visual Studio 2017, but this project should build -with the new WDK and Visual Studio when it is available. +This project is developed with Visual Studio 2017, the Windows SDK, +and the Windows Driver Kit (WDK). The WDK is only required for creating the signed WinUSB inf file. The WDK may also provide the headers for WinUSB. @@ -80,73 +107,6 @@ vscruntimeinfo.nsh and follow the instructions to bundle in the Visual Studio C Runtime required by your version of Visual Studio. Without this runtime, the panda code will not work, so without this file, the installer will refuse to build. -# Installing: - -Either build the software yourself by following the steps in the -'Developing' section, or get the panda_installer.exe file and run -it. The wizard should correctly set up the drivers. - -Since this driver is still in development, there are some issues -that may occur. If after you install the driver and then plug in your -panda (unplug it first if it was already plugged in), Windows says -the driver is missing, refer to the section below 'Dealing with self -signed drivers.' - -# Using J2534: - -After installing the J2534 drivers for the panda, you can do... nothing. -You first need to get a J2534 client that can load the drivers and talk to -the panda for you. - -A simple tool for testing J2534 drivers is DrewTech's 'J2534-1 Bus Analysis -Tool' available in the 'Other Support Applications' section of their -[Download Page](http://www.drewtech.com/downloads/). - -# Dealing with self signed drivers: - -Installation would be straightforward were it not for the USB Driver -that needs to be setup. The driver itself is only a WinUSB inf file -(no actual driver), but it still needs to be signed. - -Driver signing is a requirement of Windows starting in 8 (64 bit -versions only for some reason). If your Windows refuses to install -the driver, there are three choices: - -- Self Sign the Driver. -- Disable Driver Signature Verification -- Purchase a certificate signed by a trusted authority. - -Since self signed certificates have no chain of trust to a known -certificate authority, if you self sign, you will have to add your -cert to the root certificate store of your Windows' installation. This -is dangerous because it means anything signed with your cert will be -trusted. If you make your own cert, add a password so someone can't -copy it and screw with your computer's trust. - -Disabling Signature Verification allows you to temporarily install -drivers without a trusted signature. Once you reboot, new drivers will -need to be verified again, but any installed drivers will stay where -they are. This option is irritating if you are installing and -uninstalling the inf driver multiple times, but overall, is safer than -the custom root certificate described above. - -Purchasing a signed certificate is the best long term option, but it -is not useful for open source contributors, since the certificate will -be kept safe by the comma.ai team. Developers should use one of the -other two options. - -**Note that certificate issues apply no matter if you are building - from source or running an insaller .exe file.** - -Some people have reported that the driver installs without needing to -disable driver signing, or that visual studio correctly sets up a -temporary signing key for them. I call witchcraft because I have not -had that happen to me. The signed certificate is still the correct -thing to do in the end. - -Windows 7 will not force driver signing. This software is not tested -on anything before 7. - # Developing: - Edit and merge pandaJ2534DLL\J2534register_x64.reg to register your development J2534 DLL. @@ -154,8 +114,6 @@ on anything before 7. # ToDo Items: -- Get official signing key for WinUSB driver inf file. -- Implement TxClear and RxClear. (Requires reading vague specifications). - Apply a style-guide and consistent naming convention for Classes/Functions/Variables. - Send multiple messages (each with a different address) from a given connection at the same time. - Implement ISO14230/KWP2000 FAST (LIN communication is already supported with the raw panda USB driver). @@ -173,5 +131,14 @@ on anything before 7. relaxed to allow serialization of messages based on their address (making multiple queues, effectively one queue per address). +# Troubleshooting: +troubleshooting: +1. Install DrewTech J2534-1 Bus Analysis Tool +http://www.drewtech.com/downloads/tools/Drew%20Technologies%20Tool%20for%20J2534-1%20API%20v1.07.msi +2. Open DrewTech tool and make sure it shows "panda" as a device listed (this means registry settings are correct) +3. When DrewTech tool attempts to load the driver it will show an error if it fails +4. To figure out why the driver fails to load install Process Monitor and filter by the appropriate process name +https://docs.microsoft.com/en-us/sysinternals/downloads/procmon + # Other: Panda head ASCII art by dcau \ No newline at end of file diff --git a/panda/drivers/windows/panda.sln b/panda/drivers/windows/panda.sln index a74e4022bf600c..39c8a63e28d23f 100644 --- a/panda/drivers/windows/panda.sln +++ b/panda/drivers/windows/panda.sln @@ -1,90 +1,92 @@ - -Microsoft Visual Studio Solution File, Format Version 12.00 -# Visual Studio 14 -VisualStudioVersion = 14.0.25420.1 -MinimumVisualStudioVersion = 10.0.40219.1 -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "pandaJ2534DLL", "pandaJ2534DLL\pandaJ2534DLL.vcxproj", "{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}" - ProjectSection(ProjectDependencies) = postProject - {5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531} - EndProjectSection -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda", "panda\panda.vcxproj", "{5528AEFB-638D-49AF-B9D4-965154E7D531}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_playground", "panda_playground\panda_playground.vcxproj", "{691DB635-C272-4B98-897E-0505B970DCA9}" - ProjectSection(ProjectDependencies) = postProject - {5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531} - EndProjectSection -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda Driver Package", "panda Driver Package\panda Driver Package.vcxproj", "{BD34DB24-F5DC-4992-A74F-05FAF731ABED}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "Tests", "pandaJ2534DLL Test\pandaJ2534DLL Test.vcxproj", "{7912F978-B48C-4C5D-8BFD-5D1E22158E47}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim DLL", "ECUsim DLL\ECUsim DLL.vcxproj", "{96E0E646-EE76-444D-9A77-A0CD7F781DEB}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim CLI", "ECUsim CLI\ECUsim CLI.vcxproj", "{D99E2FCD-21A4-4065-949A-31E34E0E69D1}" -EndProject -Global - GlobalSection(SolutionConfigurationPlatforms) = preSolution - Debug|x64 = Debug|x64 - Debug|x86 = Debug|x86 - Release|x64 = Release|x64 - Release|x86 = Release|x86 - EndGlobalSection - GlobalSection(ProjectConfigurationPlatforms) = postSolution - {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x64.ActiveCfg = Debug|Win32 - {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.ActiveCfg = Debug|Win32 - {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.Build.0 = Debug|Win32 - {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x64.ActiveCfg = Release|Win32 - {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.ActiveCfg = Release|Win32 - {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.Build.0 = Release|Win32 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.ActiveCfg = Debug|x64 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.Build.0 = Debug|x64 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.ActiveCfg = Debug|Win32 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.Build.0 = Debug|Win32 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.ActiveCfg = Release|x64 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.Build.0 = Release|x64 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.ActiveCfg = Release|Win32 - {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.Build.0 = Release|Win32 - {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.ActiveCfg = Debug|x64 - {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.Build.0 = Debug|x64 - {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.ActiveCfg = Debug|Win32 - {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.Build.0 = Debug|Win32 - {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.ActiveCfg = Release|x64 - {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.Build.0 = Release|x64 - {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.ActiveCfg = Release|Win32 - {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.Build.0 = Release|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x64.ActiveCfg = Debug|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.ActiveCfg = Debug|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.Build.0 = Debug|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.Deploy.0 = Debug|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x64.ActiveCfg = Release|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.ActiveCfg = Release|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.Build.0 = Release|Win32 - {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.Deploy.0 = Release|Win32 - {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x64.ActiveCfg = Debug|Win32 - {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.ActiveCfg = Debug|Win32 - {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.Build.0 = Debug|Win32 - {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x64.ActiveCfg = Release|Win32 - {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.ActiveCfg = Release|Win32 - {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.Build.0 = Release|Win32 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.ActiveCfg = Debug|x64 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.Build.0 = Debug|x64 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.ActiveCfg = Debug|Win32 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.Build.0 = Debug|Win32 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.ActiveCfg = Release|x64 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.Build.0 = Release|x64 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.ActiveCfg = Release|Win32 - {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.Build.0 = Release|Win32 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.ActiveCfg = Debug|x64 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.Build.0 = Debug|x64 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.ActiveCfg = Debug|Win32 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.Build.0 = Debug|Win32 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.ActiveCfg = Release|x64 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.Build.0 = Release|x64 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.ActiveCfg = Release|Win32 - {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.Build.0 = Release|Win32 - EndGlobalSection - GlobalSection(SolutionProperties) = preSolution - HideSolutionNode = FALSE - EndGlobalSection -EndGlobal + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.27130.2027 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "pandaJ2534DLL", "pandaJ2534DLL\pandaJ2534DLL.vcxproj", "{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda", "panda\panda.vcxproj", "{5528AEFB-638D-49AF-B9D4-965154E7D531}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_playground", "panda_playground\panda_playground.vcxproj", "{691DB635-C272-4B98-897E-0505B970DCA9}" + ProjectSection(ProjectDependencies) = postProject + {5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531} + EndProjectSection +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda Driver Package", "panda Driver Package\panda Driver Package.vcxproj", "{BD34DB24-F5DC-4992-A74F-05FAF731ABED}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "Tests", "pandaJ2534DLL Test\pandaJ2534DLL Test.vcxproj", "{7912F978-B48C-4C5D-8BFD-5D1E22158E47}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim DLL", "ECUsim DLL\ECUsim DLL.vcxproj", "{96E0E646-EE76-444D-9A77-A0CD7F781DEB}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim CLI", "ECUsim CLI\ECUsim CLI.vcxproj", "{D99E2FCD-21A4-4065-949A-31E34E0E69D1}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_shared", "panda_shared\panda_shared.vcxitems", "{0C843279-68C7-4679-AE51-9BC463D50D1C}" +EndProject +Global + GlobalSection(SharedMSBuildProjectFiles) = preSolution + panda_shared\panda_shared.vcxitems*{0c843279-68c7-4679-ae51-9bc463d50d1c}*SharedItemsImports = 9 + panda_shared\panda_shared.vcxitems*{5528aefb-638d-49af-b9d4-965154e7d531}*SharedItemsImports = 4 + panda_shared\panda_shared.vcxitems*{a2bb18a5-f26b-48d6-bbb5-b83d64473c77}*SharedItemsImports = 4 + EndGlobalSection + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x64.ActiveCfg = Debug|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.ActiveCfg = Debug|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.Build.0 = Debug|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x64.ActiveCfg = Release|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.ActiveCfg = Release|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.Build.0 = Release|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.ActiveCfg = Debug|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.Build.0 = Debug|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.ActiveCfg = Debug|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.Build.0 = Debug|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.ActiveCfg = Release|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.Build.0 = Release|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.ActiveCfg = Release|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.Build.0 = Release|Win32 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.ActiveCfg = Debug|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.Build.0 = Debug|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.ActiveCfg = Debug|Win32 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.Build.0 = Debug|Win32 + {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.ActiveCfg = Release|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.Build.0 = Release|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.ActiveCfg = Release|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x64.ActiveCfg = Debug|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.ActiveCfg = Debug|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x64.ActiveCfg = Release|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.ActiveCfg = Release|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x64.ActiveCfg = Debug|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.ActiveCfg = Debug|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.Build.0 = Debug|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x64.ActiveCfg = Release|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.ActiveCfg = Release|Win32 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.ActiveCfg = Debug|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.Build.0 = Debug|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.ActiveCfg = Debug|Win32 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.Build.0 = Debug|Win32 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.ActiveCfg = Release|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.Build.0 = Release|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.ActiveCfg = Release|Win32 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.ActiveCfg = Debug|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.Build.0 = Debug|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.ActiveCfg = Debug|Win32 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.Build.0 = Debug|Win32 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.ActiveCfg = Release|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.Build.0 = Release|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.ActiveCfg = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection + GlobalSection(ExtensibilityGlobals) = postSolution + SolutionGuid = {8AF3826E-406A-4F1C-BA80-B4D7FD4B52E1} + EndGlobalSection + GlobalSection(Performance) = preSolution + HasPerformanceSessions = true + EndGlobalSection +EndGlobal diff --git a/panda/drivers/windows/panda/panda.vcxproj b/panda/drivers/windows/panda/panda.vcxproj index 147c58ca149fb7..22879c7cae8e2c 100644 --- a/panda/drivers/windows/panda/panda.vcxproj +++ b/panda/drivers/windows/panda/panda.vcxproj @@ -1,193 +1,189 @@ - - - - - Debug - Win32 - - - Release - Win32 - - - Debug - x64 - - - Release - x64 - - - - {5528AEFB-638D-49AF-B9D4-965154E7D531} - Win32Proj - panda - 8.1 - - - - DynamicLibrary - true - v140 - Unicode - - - DynamicLibrary - false - v140 - true - Unicode - - - DynamicLibrary - true - v140 - Unicode - - - DynamicLibrary - false - v140 - true - Unicode - - - - - - - - - - - - - - - - - - - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - false - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - false - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - - Use - Level3 - Disabled - WIN32;_DEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) - true - false - - - Windows - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib - - - - - Use - Level3 - Disabled - _DEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) - true - - - Windows - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib - - - - - Level3 - Use - MaxSpeed - true - true - WIN32;NDEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) - true - - - Windows - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib - - - - - Level3 - Use - MaxSpeed - true - true - NDEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) - true - - - Windows - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib - - - - - - - - - - - - - false - - - false - - - false - - - false - - - - - - Create - Create - Create - Create - - - - - - - - - - - + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {5528AEFB-638D-49AF-B9D4-965154E7D531} + Win32Proj + panda + 10.0.16299.0 + + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + false + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + Use + Level3 + Disabled + _DEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + + + + + false + + + false + + + false + + + false + + + + + Create + Create + Create + Create + + + + + + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda/panda.vcxproj.filters b/panda/drivers/windows/panda/panda.vcxproj.filters index cded701a31c4b4..afddad6e8b7f97 100644 --- a/panda/drivers/windows/panda/panda.vcxproj.filters +++ b/panda/drivers/windows/panda/panda.vcxproj.filters @@ -1,58 +1,43 @@ - - - - - {4FC737F1-C7A5-4376-A066-2A32D752A2FF} - cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx - - - {93995380-89BD-4b04-88EB-625FBE52EBFB} - h;hh;hpp;hxx;hm;inl;inc;xsd - - - {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} - rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms - - - - - Header Files - - - Header Files - - - Header Files - - - Header Files - - - Header Files - - - - - Source Files - - - Source Files - - - Source Files - - - Source Files - - - - - Resource Files - - - - - Resource Files - - + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + + + Resource Files + + + + + Resource Files + + \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp index 1effc4914511e1..8a9161475c90bd 100644 --- a/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp +++ b/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp @@ -1,7 +1,7 @@ #include "stdafx.h" #include "Loader4.h" #include "pandaJ2534DLL/J2534_v0404.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" #include "Timer.h" #include "ECUsim DLL\ECUsim.h" #include "TestHelpers.h" diff --git a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp index 62096d118138bb..1281eb9d616c43 100644 --- a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp +++ b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp @@ -2,7 +2,7 @@ #include "TestHelpers.h" #include "Loader4.h" #include "pandaJ2534DLL/J2534_v0404.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" #include "Timer.h" using namespace Microsoft::VisualStudio::CppUnitTestFramework; diff --git a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h index 17dcee5f540502..9df59d7b5e1ac0 100644 --- a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h +++ b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h @@ -1,7 +1,7 @@ #pragma once #include "stdafx.h" #include "pandaJ2534DLL/J2534_v0404.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" using namespace Microsoft::VisualStudio::CppUnitTestFramework; diff --git a/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp index 774b8ed31c7483..674569acccafd3 100644 --- a/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp +++ b/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp @@ -1,7 +1,7 @@ #include "stdafx.h" #include "Loader4.h" #include "pandaJ2534DLL/J2534_v0404.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" #include "Timer.h" #include "ECUsim DLL\ECUsim.h" #include "TestHelpers.h" diff --git a/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj index 56923823ba9652..f19c743461d661 100644 --- a/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj +++ b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj @@ -1,125 +1,122 @@ - - - - - Debug - Win32 - - - Release - Win32 - - - - {7912F978-B48C-4C5D-8BFD-5D1E22158E47} - Win32Proj - pandaJ2534DLLTest - 8.1 - Tests - - - - DynamicLibrary - true - v140 - Unicode - false - - - DynamicLibrary - false - v140 - true - Unicode - false - - - - - - - - - - - - - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - - Use - Level3 - Disabled - $(VCInstallDir)UnitTest\include;%(AdditionalIncludeDirectories);$(SolutionDir) - WIN32;_DEBUG;%(PreprocessorDefinitions) - true - - - Windows - $(VCInstallDir)UnitTest\lib;%(AdditionalLibraryDirectories) - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib - - - - - Level3 - Use - MaxSpeed - true - true - $(VCInstallDir)UnitTest\include;%(AdditionalIncludeDirectories);$(SolutionDir) - WIN32;NDEBUG;%(PreprocessorDefinitions) - true - - - Windows - true - true - $(VCInstallDir)UnitTest\lib;%(AdditionalLibraryDirectories) - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib - - - - - - - - - - - - - - - - - Create - Create - - - - - - - - {96e0e646-ee76-444d-9a77-a0cd7f781deb} - - - {a2bb18a5-f26b-48d6-bbb5-b83d64473c77} - - - {5528aefb-638d-49af-b9d4-965154e7d531} - - - - - + + + + + Debug + Win32 + + + Release + Win32 + + + + {7912F978-B48C-4C5D-8BFD-5D1E22158E47} + Win32Proj + pandaJ2534DLLTest + 10.0.16299.0 + Tests + + + + DynamicLibrary + true + v141 + Unicode + false + + + DynamicLibrary + false + v141 + true + Unicode + false + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + $(VCInstallDir)UnitTest\include;%(AdditionalIncludeDirectories);$(SolutionDir) + WIN32;_DEBUG;%(PreprocessorDefinitions) + true + + + Windows + $(VCInstallDir)UnitTest\lib;%(AdditionalLibraryDirectories) + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Level3 + Use + MaxSpeed + true + true + $(VCInstallDir)UnitTest\include;%(AdditionalIncludeDirectories);$(SolutionDir) + WIN32;NDEBUG;%(PreprocessorDefinitions) + true + + + Windows + true + true + $(VCInstallDir)UnitTest\lib;%(AdditionalLibraryDirectories) + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + + + + + + + + + + + + + Create + Create + + + + + + + + {96e0e646-ee76-444d-9a77-a0cd7f781deb} + + + {a2bb18a5-f26b-48d6-bbb5-b83d64473c77} + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp index 65e549c50c00a5..51b0bfcf2f60b5 100644 --- a/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp +++ b/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp @@ -1,5 +1,5 @@ #include "stdafx.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" #include "TestHelpers.h" #include diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp index 358158bcb423b9..aa364b0f8a323c 100644 --- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp @@ -33,6 +33,7 @@ long J2534Connection::PassThruReadMsgs(PASSTHRU_MSG *pMsg, unsigned long *pNumMs messageRxBuff_mutex.unlock(); if (Timeout == 0) break; + Sleep(2); continue; } @@ -146,16 +147,35 @@ long J2534Connection::PassThruIoctl(unsigned long IoctlID, void *pInput, void *p return STATUS_NOERROR; } -long J2534Connection::init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput) { return STATUS_NOERROR; } -long J2534Connection::initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput) { return STATUS_NOERROR; } -long J2534Connection::clearTXBuff() { return STATUS_NOERROR; } +long J2534Connection::init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput) { return ERR_FAILED; } +long J2534Connection::initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput) { return ERR_FAILED; } +long J2534Connection::clearTXBuff() { + if (auto panda_ps = this->panda_dev.lock()) { + synchronized(staged_writes_lock) { + this->txbuff = {}; + panda_ps->panda->can_clear(panda::PANDA_CAN1_TX); + } + } + return STATUS_NOERROR; +} long J2534Connection::clearRXBuff() { - synchronized(messageRxBuff_mutex) { - this->messageRxBuff = {}; + if (auto panda_ps = this->panda_dev.lock()) { + synchronized(messageRxBuff_mutex) { + this->messageRxBuff = {}; + panda_ps->panda->can_clear(panda::PANDA_CAN_RX); + } } return STATUS_NOERROR; } -long J2534Connection::clearPeriodicMsgs() { return STATUS_NOERROR; } +long J2534Connection::clearPeriodicMsgs() { + for (int i = 0; i < this->periodicMessages.size(); i++) { + if (periodicMessages[i] == nullptr) continue; + this->periodicMessages[i]->cancel(); + this->periodicMessages[i] = nullptr; + } + + return STATUS_NOERROR; +} long J2534Connection::clearMsgFilters() { for (auto& filter : this->filters) filter = nullptr; return STATUS_NOERROR; @@ -202,6 +222,7 @@ void J2534Connection::processIOCTLSetConfig(unsigned long Parameter, unsigned lo switch (Parameter) { case DATA_RATE: // 5-500000 this->setBaud(Value); + break; case LOOPBACK: // 0 (OFF), 1 (ON) [0] this->loopback = (Value != 0); break; @@ -236,6 +257,11 @@ void J2534Connection::processIOCTLSetConfig(unsigned long Parameter, unsigned lo default: printf("Got unknown SET code %X\n", Parameter); } + + // reserved parameters usually mean special equiptment is required + if (Parameter >= 0x20) { + throw ERR_NOT_SUPPORTED; + } } unsigned long J2534Connection::processIOCTLGetConfig(unsigned long Parameter) { diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h index cdb215018b3fd1..70f25a1063f09f 100644 --- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h @@ -1,5 +1,5 @@ #pragma once -#include "panda/panda.h" +#include "panda_shared/panda.h" #include "J2534_v0404.h" #include "synchronize.h" #include "J2534Frame.h" diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h index 4dd950b3907da6..3971351eea369a 100644 --- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h @@ -1,7 +1,7 @@ #pragma once #include "J2534Connection.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" #define val_is_29bit(num) check_bmask(num, CAN_29BIT_ID) diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp index 2b9d97cb64e620..a83f6f433135f2 100644 --- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp @@ -43,7 +43,7 @@ std::shared_ptr J2534Connection_ISO15765::parseMessageTx(PASSTHRU_MSG void J2534Connection_ISO15765::processMessage(const J2534Frame& msg) { if (msg.ProtocolID != CAN) return; - int fid = get_matching_in_fc_filter_id(msg); + int fid = get_matching_in_fc_filter_id(msg, this->Flags); if (fid == -1) return; auto filter = this->filters[fid]; @@ -136,6 +136,9 @@ void J2534Connection_ISO15765::processMessage(const J2534Frame& msg) { if (flowfilter.size() > 4) flowstrlresp += flowfilter[4]; flowstrlresp += std::string("\x30\x00\x00", 3); + if (check_bmask(filter->flags, ISO15765_FRAME_PAD)) { + flowstrlresp += std::string(8 - flowstrlresp.size(), '\x00'); + } if (auto panda_dev_sp = this->panda_dev.lock()) { panda_dev_sp->panda->can_send(flow_addr, val_is_29bit(msg.RxStatus), (const uint8_t *)flowstrlresp.c_str(), (uint8_t)flowstrlresp.size(), panda::PANDA_CAN1); diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h index ddbf2dc2aa5ed9..beb9f012e09976 100644 --- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h @@ -25,7 +25,7 @@ class J2534Connection_ISO15765 : public J2534Connection { int get_matching_out_fc_filter_id(const std::string & msgdata, unsigned long flags, unsigned long flagmask); - int get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask = CAN_29BIT_ID); + int get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask); virtual unsigned long validateTxMsg(PASSTHRU_MSG* msg); diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h b/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h index 5c991c5082e903..2549216b6f1fac 100644 --- a/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h @@ -1,6 +1,6 @@ #pragma once #include "J2534_v0404.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" /*A move convenient container for J2534 Messages than the static buffer provided by default.*/ class J2534Frame { @@ -10,7 +10,7 @@ class J2534Frame { J2534Frame(const panda::PANDA_CAN_MSG& msg_in) { ProtocolID = CAN; - ExtraDataIndex = 0; + ExtraDataIndex = msg_in.len + 4; Data.reserve(msg_in.len + 4); Data += msg_in.addr >> 24; Data += (msg_in.addr >> 16) & 0xFF; diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp index abcf3f6a472ea3..023088d3c61ea6 100644 --- a/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp @@ -95,7 +95,7 @@ BOOL MessageTx_ISO15765::checkTxReceipt(J2534Frame frame) { J2534Frame outframe(ISO15765); outframe.Timestamp = frame.Timestamp; - outframe.RxStatus = TX_INDICATION | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID)); + outframe.RxStatus = TX_MSG_TYPE | TX_INDICATION | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID)); outframe.Data = frame.Data.substr(0, addressLength()); conn_sp->addMsgToRxQueue(outframe); diff --git a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp index 64da8e2c3d813e..1b961579e079ab 100644 --- a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp +++ b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp @@ -8,11 +8,15 @@ PandaJ2534Device::PandaJ2534Device(std::unique_ptr new_panda) : tx this->panda->set_esp_power(FALSE); this->panda->set_safety_mode(panda::SAFETY_ALLOUTPUT); this->panda->set_can_loopback(FALSE); - this->panda->set_alt_setting(1); + this->panda->set_alt_setting(0); - DWORD canListenThreadID; this->thread_kill_event = CreateEvent(NULL, TRUE, FALSE, NULL); - this->can_thread_handle = CreateThread(NULL, 0, _can_recv_threadBootstrap, (LPVOID)this, 0, &canListenThreadID); + + DWORD canListenThreadID; + this->can_recv_handle = CreateThread(NULL, 0, _can_recv_threadBootstrap, (LPVOID)this, 0, &canListenThreadID); + + DWORD canProcessThreadID; + this->can_process_handle = CreateThread(NULL, 0, _can_process_threadBootstrap, (LPVOID)this, 0, &canProcessThreadID); DWORD flowControlSendThreadID; this->flow_control_wakeup_event = CreateEvent(NULL, TRUE, FALSE, NULL); @@ -21,8 +25,11 @@ PandaJ2534Device::PandaJ2534Device(std::unique_ptr new_panda) : tx PandaJ2534Device::~PandaJ2534Device() { SetEvent(this->thread_kill_event); - DWORD res = WaitForSingleObject(this->can_thread_handle, INFINITE); - CloseHandle(this->can_thread_handle); + DWORD res = WaitForSingleObject(this->can_recv_handle, INFINITE); + CloseHandle(this->can_recv_handle); + + res = WaitForSingleObject(this->can_process_handle, INFINITE); + CloseHandle(this->can_process_handle); res = WaitForSingleObject(this->flow_control_thread_handle, INFINITE); CloseHandle(this->flow_control_thread_handle); @@ -67,11 +74,28 @@ DWORD PandaJ2534Device::addChannel(std::shared_ptr& conn, unsig } DWORD PandaJ2534Device::can_recv_thread() { - DWORD err = TRUE; - while (err) { - std::vector msg_recv; - err = this->panda->can_recv_async(this->thread_kill_event, msg_recv); - for (auto msg_in : msg_recv) { + this->panda->can_clear(panda::PANDA_CAN_RX); + this->panda->can_rx_q_push(this->thread_kill_event); + + return 0; +} + +DWORD PandaJ2534Device::can_process_thread() { + panda::PANDA_CAN_MSG msg_recv[CAN_RX_MSG_LEN]; + + while (true) { + if (!WaitForSingleObject(this->thread_kill_event, 0)) { + break; + } + + int count = 0; + this->panda->can_rx_q_pop(msg_recv, count); + if (count == 0) { + continue; + } + + for (int i = 0; i < count; i++) { + auto msg_in = msg_recv[i]; J2534Frame msg_out(msg_in); if (msg_in.is_receipt) { @@ -112,7 +136,7 @@ DWORD PandaJ2534Device::can_recv_thread() { } } else { for (auto& conn : this->connections) - if (conn->isProtoCan() && conn->getPort() == msg_in.bus) + if (conn != nullptr && conn->isProtoCan() && conn->getPort() == msg_in.bus) conn->processMessage(msg_out); } } diff --git a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h index 3e5880c955c78c..32004ffba5ea14 100644 --- a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h +++ b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h @@ -5,7 +5,7 @@ #include #include #include "J2534_v0404.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" #include "synchronize.h" #include "Action.h" #include "MessageTx.h" @@ -55,12 +55,18 @@ class PandaJ2534Device { private: HANDLE thread_kill_event; - HANDLE can_thread_handle; + HANDLE can_recv_handle; static DWORD WINAPI _can_recv_threadBootstrap(LPVOID This) { return ((PandaJ2534Device*)This)->can_recv_thread(); } DWORD can_recv_thread(); + HANDLE can_process_handle; + static DWORD WINAPI _can_process_threadBootstrap(LPVOID This) { + return ((PandaJ2534Device*)This)->can_process_thread(); + } + DWORD can_process_thread(); + HANDLE flow_control_wakeup_event; HANDLE flow_control_thread_handle; static DWORD WINAPI _msg_tx_threadBootstrap(LPVOID This) { diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp index 2e706f507d9994..096e4419883928 100644 --- a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp +++ b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp @@ -5,7 +5,7 @@ #include "stdafx.h" #include "J2534_v0404.h" -#include "panda/panda.h" +#include "panda_shared/panda.h" #include "J2534Connection.h" #include "J2534Connection_CAN.h" #include "J2534Connection_ISO15765.h" @@ -57,7 +57,7 @@ long ret_code(long code) { return code; } -#define EXTRACT_DID(CID) (CID & 0xFFFF) +#define EXTRACT_DID(CID) ((CID & 0xFFFF) - 1) #define EXTRACT_CID(CID) ((CID >> 16) & 0xFFFF) long check_valid_DeviceID(unsigned long DeviceID) { @@ -68,7 +68,7 @@ long check_valid_DeviceID(unsigned long DeviceID) { } long check_valid_ChannelID(unsigned long ChannelID) { - uint16_t dev_id = EXTRACT_DID(ChannelID);; + uint16_t dev_id = EXTRACT_DID(ChannelID); uint16_t con_id = EXTRACT_CID(ChannelID); if (pandas.size() <= dev_id || pandas[dev_id] == nullptr) @@ -117,7 +117,7 @@ PANDAJ2534DLL_API long PTAPI PassThruOpen(void *pName, unsigned long *pDevice panda_index = pandas.size()-1; } - *pDeviceID = panda_index; + *pDeviceID = panda_index + 1; // TIS doesn't like it when ID == 0 return ret_code(STATUS_NOERROR); } PANDAJ2534DLL_API long PTAPI PassThruClose(unsigned long DeviceID) { @@ -140,14 +140,12 @@ PANDAJ2534DLL_API long PTAPI PassThruConnect(unsigned long DeviceID, unsigned lo switch (ProtocolID) { //SW seems to refer to Single Wire. https://www.nxp.com/files-static/training_pdf/20451_BUS_COMM_WBT.pdf //SW_ protocols may be touched on here: https://www.iso.org/obp/ui/#iso:std:iso:22900:-2:ed-1:v1:en - case J1850VPW: //These protocols are outdated and will not be supported. HDS wants them to not fail to open. - case J1850PWM: - case J1850VPW_PS: - case J1850PWM_PS: + //case J1850VPW: // These protocols are outdated and will not be supported. HDS wants them to not fail to open. + //case J1850PWM: // ^-- it appears HDS no longer needs this, and TIS needs it disabled --^ + //case J1850VPW_PS: + //case J1850PWM_PS: case ISO9141: //This protocol could be implemented if 5 BAUD init support is added to the panda. case ISO9141_PS: - conn = std::make_shared(panda, ProtocolID, Flags, BaudRate); - break; case ISO14230: //Only supporting Fast init until panda adds support for 5 BAUD init. case ISO14230_PS: conn = std::make_shared(panda, ProtocolID, Flags, BaudRate); @@ -263,8 +261,7 @@ PANDAJ2534DLL_API long PTAPI PassThruReadVersion(unsigned long DeviceID, char *p } else { j2534dll_ver = GetProductAndVersion(pandalib_filename); } - std::string pandalib_ver = GetProductAndVersion(_T("panda.dll")); - std::string fullver = "(" + j2534dll_ver + "; " + pandalib_ver + ")"; + std::string fullver = "(" + j2534dll_ver + ")"; strcpy_s(pDllVersion, 80, fullver.c_str()); strcpy_s(pApiVersion, 80, J2534_APIVER_NOVEMBER_2004); diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj index 065fa69adcfcbf..fd5eac56dd4d4a 100644 --- a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj +++ b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj @@ -1,152 +1,148 @@ - - - - - Debug - Win32 - - - Release - Win32 - - - - {A2BB18A5-F26B-48D6-BBB5-B83D64473C77} - Win32Proj - pandaJ2534DLL - 8.1 - - - - DynamicLibrary - true - v140 - Unicode - - - DynamicLibrary - false - v140 - true - Unicode - - - - - - - - - - - - - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - pandaJ2534_0404_32 - - - false - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - pandaJ2534_0404_32 - - - - Use - Level3 - Disabled - WIN32;_DEBUG;_WINDOWS;_USRDLL;PANDAJ2534DLL_EXPORTS;%(PreprocessorDefinitions) - true - $(SolutionDir); - - - Windows - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;$(OutDir)panda.lib - - - - - Level3 - Use - MaxSpeed - true - true - WIN32;NDEBUG;_WINDOWS;_USRDLL;PANDAJ2534DLL_EXPORTS;%(PreprocessorDefinitions) - true - $(SolutionDir); - - - Windows - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;$(OutDir)panda.lib - - - - - - - - - - - - - - - - - - - - - - - - - - - - - false - - - false - - - - - - - - - - - - - - - Create - Create - - - - - - {5528aefb-638d-49af-b9d4-965154e7d531} - - - - - - - - - - - + + + + + Debug + Win32 + + + Release + Win32 + + + + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77} + Win32Proj + pandaJ2534DLL + 10.0.16299.0 + + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + pandaJ2534_0404_32 + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + pandaJ2534_0404_32 + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_WINDOWS;_USRDLL;PANDAJ2534DLL_EXPORTS;%(PreprocessorDefinitions) + true + $(SolutionDir); + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_WINDOWS;_USRDLL;PANDAJ2534DLL_EXPORTS;%(PreprocessorDefinitions) + true + $(SolutionDir); + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib + + + + + + + + + + + + + + + + + + + + + + + + + + + + + false + + + false + + + + + + + + + + + + + + + Create + Create + + + + + + + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda_install.nsi b/panda/drivers/windows/panda_install.nsi index 81ecc3c872df42..47a4423f91b940 100644 --- a/panda/drivers/windows/panda_install.nsi +++ b/panda/drivers/windows/panda_install.nsi @@ -1,5 +1,5 @@ !define J2534_Reg_Path "Software\PassThruSupport.04.04\comma.ai - panda" -!define Install_Name "panda J2534 Drivers" +!define Install_Name "panda J2534 driver" ;NOTE! The panda software requires a VC runtime to be installed in order to work. ;This installer must be bundled with the appropriate runtime installer, and have @@ -21,10 +21,10 @@ Unicode true # Set the installer display name -Name "panda Driver" +Name "${Install_Name}" # set the name of the installer -Outfile "panda install.exe" +Outfile "${Install_Name} install.exe" ; The default installation directory InstallDir $PROGRAMFILES\comma.ai\panda @@ -63,18 +63,19 @@ VIProductVersion "1.0.0.0" ;-------------------------------- ; Install Sections -Section "panda driver (required)" +Section "prerequisites" SectionIn RO SetOutPath "$INSTDIR" + File "panda.ico" ;If the visual studio version this project is compiled with changes, this section ;must be revisited. The registry key must be changed, and the VS redistributable ;binary must be updated to the VS version used. ClearErrors - ReadRegStr $0 HKLM ${VCRuntimeRegKey} "Version" + ReadRegStr $0 HKCR ${VCRuntimeRegKey} "Version" ${If} ${Errors} DetailPrint "Installing Visual Studio C Runtime..." File "${VCRuntimeSetupPath}\${VCRuntimeSetupFile}" @@ -87,35 +88,22 @@ Section "panda driver (required)" Delete "$INSTDIR\${VCRuntimeSetupFile}" ;Do the rest of the install - SetOutPath "$INSTDIR\driver" + ; SetOutPath "$INSTDIR\driver" ; The inf file works for both 32 and 64 bit. - File "Debug_x86\panda Driver Package\panda.inf" - File "Debug_x86\panda Driver Package\panda.cat" - ${DisableX64FSRedirection} - nsExec::ExecToLog '"$SYSDIR\PnPutil.exe" /a "$INSTDIR\driver\panda.inf"' - ${EnableX64FSRedirection} - - SetOutPath $SYSDIR - - File Release_x86\panda.dll - - ${If} ${RunningX64} - ${DisableX64FSRedirection} - ;Note that the x64 VS redistributable is not installed to prevent bloat. - ;If you are the rare person who uses the 64 bit raw panda driver, please - ;install the correct x64 VS runtime manually. - File Release_x64\panda.dll - ${EnableX64FSRedirection} - ${EndIf} + ; File "Debug_x86\panda Driver Package\panda.inf" + ; File "Debug_x86\panda Driver Package\panda.cat" + ; ${DisableX64FSRedirection} + ; nsExec::ExecToLog '"$SYSDIR\PnPutil.exe" /a "$INSTDIR\driver\panda.inf"' + ; ${EnableX64FSRedirection} ; Write the installation path into the registry - WriteRegStr HKLM "SOFTWARE\panda J2534 Drivers" "Install_Dir" "$INSTDIR" + WriteRegStr HKLM "SOFTWARE\${Install_Name}" "Install_Dir" "$INSTDIR" ; Write the uninstall keys for Windows - ;WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayVersion" "" - WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayIcon" '"$SYSDIR\panda.dll",0' - WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayName" "panda J2534 Drivers" + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayVersion" "" + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayIcon" '"$INSTDIR\panda.ico",0' + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayName" "${Install_Name}" WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "Publisher" "comma.ai" WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "UninstallString" '"$INSTDIR\uninstall.exe"' WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "URLInfoAbout" "https://github.com/commaai/panda/" @@ -127,19 +115,6 @@ Section "panda driver (required)" SectionEnd -Section "panda devel lib/header" - - SetOutPath "$INSTDIR\devel" - File panda\panda.h - - SetOutPath "$INSTDIR\devel\x86" - File Release_x86\panda.lib - - SetOutPath "$INSTDIR\devel\x64" - File Release_x64\panda.lib - -SectionEnd - Section "J2534 Driver" SetOutPath $INSTDIR @@ -165,6 +140,32 @@ Section "J2534 Driver" SectionEnd +Section /o "Development lib/header" + + SetOutPath $SYSDIR + + File Release_x86\panda.dll + + ${If} ${RunningX64} + ${DisableX64FSRedirection} + ;Note that the x64 VS redistributable is not installed to prevent bloat. + ;If you are the rare person who uses the 64 bit raw panda driver, please + ;install the correct x64 VS runtime manually. + File Release_x64\panda.dll + ${EnableX64FSRedirection} + ${EndIf} + + SetOutPath "$INSTDIR\devel" + File panda_shared\panda.h + + SetOutPath "$INSTDIR\devel\x86" + File Release_x86\panda.lib + + SetOutPath "$INSTDIR\devel\x64" + File Release_x64\panda.lib + +SectionEnd + ;-------------------------------- ; Uninstaller Section "Uninstall" @@ -176,9 +177,9 @@ Section "Uninstall" ; if Microsoft wants these inf files to be removed. ; Consider https://blog.sverrirs.com/2015/12/creating-windows-installer-and.html ; These lines just remove the inf backups. - Delete "$INSTDIR\driver\panda.inf" - Delete "$INSTDIR\driver\panda.cat" - RMDir "$INSTDIR\driver" + ; Delete "$INSTDIR\driver\panda.inf" + ; Delete "$INSTDIR\driver\panda.cat" + ; RMDir "$INSTDIR\driver" ; Remove WinUSB driver library Delete $SYSDIR\panda.dll @@ -204,6 +205,7 @@ Section "Uninstall" ; Remove files and uninstaller Delete "$INSTDIR\uninstall.exe" Delete "$INSTDIR\pandaJ2534_0404_32.dll" + Delete "$INSTDIR\panda.ico" ; Remove directories used RMDir "$INSTDIR" diff --git a/panda/drivers/windows/panda_playground/panda_playground.vcxproj b/panda/drivers/windows/panda_playground/panda_playground.vcxproj index 0063bebcebaa8a..2b5f3120c34721 100644 --- a/panda/drivers/windows/panda_playground/panda_playground.vcxproj +++ b/panda/drivers/windows/panda_playground/panda_playground.vcxproj @@ -1,191 +1,191 @@ - - - - - Debug - Win32 - - - Release - Win32 - - - Debug - x64 - - - Release - x64 - - - - {691DB635-C272-4B98-897E-0505B970DCA9} - Win32Proj - panda_playground - 8.1 - - - - Application - true - v140 - Unicode - - - Application - false - v140 - true - Unicode - - - Application - true - v140 - Unicode - - - Application - false - v140 - true - Unicode - - - - - - - - - - - - - - - - - - - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - $(ProjectName)2 - - - true - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - $(ProjectName) - - - false - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - false - $(SolutionDir)$(Configuration)_$(PlatformShortName)\ - - - - Use - Level3 - Disabled - WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib - - - - - Use - Level3 - Disabled - _DEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib - - - - - Level3 - Use - MaxSpeed - true - true - WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib - - - - - Level3 - Use - MaxSpeed - true - true - NDEBUG;_CONSOLE;%(PreprocessorDefinitions) - true - %(AdditionalIncludeDirectories);$(SolutionDir) - - - Console - true - true - true - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib - - - - - - - - - - - - - - - - Create - Create - Create - Create - - - - - {96e0e646-ee76-444d-9a77-a0cd7f781deb} - - - {a2bb18a5-f26b-48d6-bbb5-b83d64473c77} - - - {5528aefb-638d-49af-b9d4-965154e7d531} - - - - - + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {691DB635-C272-4B98-897E-0505B970DCA9} + Win32Proj + panda_playground + 10.0.16299.0 + + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + $(ProjectName)2 + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + $(ProjectName) + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + Use + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + + + + + + + + + + + + Create + Create + Create + Create + + + + + {96e0e646-ee76-444d-9a77-a0cd7f781deb} + + + {a2bb18a5-f26b-48d6-bbb5-b83d64473c77} + + + {5528aefb-638d-49af-b9d4-965154e7d531} + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda/device.cpp b/panda/drivers/windows/panda_shared/device.cpp similarity index 99% rename from panda/drivers/windows/panda/device.cpp rename to panda/drivers/windows/panda_shared/device.cpp index a204610000c8be..83e021b7994ad4 100644 --- a/panda/drivers/windows/panda/device.cpp +++ b/panda/drivers/windows/panda_shared/device.cpp @@ -1,10 +1,13 @@ #include "stdafx.h" + #include #include #include #include +#include + #include "device.h" using namespace panda; diff --git a/panda/drivers/windows/panda/device.h b/panda/drivers/windows/panda_shared/device.h similarity index 97% rename from panda/drivers/windows/panda/device.h rename to panda/drivers/windows/panda_shared/device.h index 3b404857cf5cb3..f11baa1c67c887 100644 --- a/panda/drivers/windows/panda/device.h +++ b/panda/drivers/windows/panda_shared/device.h @@ -4,7 +4,6 @@ // // Define below GUIDs // -#include "stdafx.h" #include #include diff --git a/panda/drivers/windows/panda/panda.cpp b/panda/drivers/windows/panda_shared/panda.cpp similarity index 77% rename from panda/drivers/windows/panda/panda.cpp rename to panda/drivers/windows/panda_shared/panda.cpp index 79ec08edc29967..5f711b02aa28a1 100644 --- a/panda/drivers/windows/panda/panda.cpp +++ b/panda/drivers/windows/panda_shared/panda.cpp @@ -1,7 +1,7 @@ // panda.cpp : Defines the exported functions for the DLL application. // - #include "stdafx.h" + #include "device.h" #include "panda.h" @@ -13,13 +13,6 @@ using namespace panda; -#pragma pack(1) -typedef struct _PANDA_CAN_MSG_INTERNAL { - uint32_t rir; - uint32_t f2; - uint8_t dat[8]; -} PANDA_CAN_MSG_INTERNAL; - Panda::Panda( WINUSB_INTERFACE_HANDLE WinusbHandle, HANDLE DeviceHandle, @@ -28,6 +21,7 @@ Panda::Panda( ) : usbh(WinusbHandle), devh(DeviceHandle), devPath(devPath_), sn(sn_) { printf("CREATED A PANDA %s\n", this->sn.c_str()); this->set_can_loopback(FALSE); + this->set_raw_io(TRUE); this->set_alt_setting(0); } @@ -167,7 +161,8 @@ bool Panda::set_alt_setting(UCHAR alt_setting) { this->set_can_loopback(TRUE); Sleep(20); // Give time for any sent messages to appear in the RX buffer. this->can_clear(PANDA_CAN_RX); - for (int i = 0; i < 2; i++) { + // send 4 messages becaus can_recv reads 4 messages at a time + for (int i = 0; i < 4; i++) { printf("Sending PAD %d\n", i); if (this->can_send(0x7FF, FALSE, {}, 0, PANDA_CAN1) == FALSE) { auto err = GetLastError(); @@ -177,14 +172,8 @@ bool Panda::set_alt_setting(UCHAR alt_setting) { Sleep(10); //this->can_clear(PANDA_CAN_RX); - std::vector msg_recv; - if (alt_setting == 1) { - //Read the messages so they do not contaimnate the real message stream. - auto err = this->can_recv_async(NULL, msg_recv, 1000); - } - else { - msg_recv = this->can_recv(); - } + //Read the messages so they do not contaimnate the real message stream. + this->can_recv(); //this->set_can_loopback(FALSE); this->set_can_loopback(loopback_backup); @@ -203,6 +192,17 @@ UCHAR Panda::get_current_alt_setting() { return alt_setting; } +bool Panda::set_raw_io(bool val) { + UCHAR raw_io = val; + if (!WinUsb_SetPipePolicy(this->usbh, 0x81, RAW_IO, sizeof(raw_io), &raw_io)) { + _tprintf(_T(" Error setting usb raw I/O pipe policy %d, Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + return FALSE; + } + + return TRUE; +} + PANDA_HEALTH Panda::get_health() { WINUSB_SETUP_PACKET SetupPacket; @@ -351,69 +351,85 @@ bool Panda::can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t l return this->can_send_many(std::vector{msg}); } -void Panda::parse_can_recv(std::vector& msg_recv, char *buff, int retcount) { - for (int i = 0; i < retcount; i += sizeof(PANDA_CAN_MSG_INTERNAL)) { - PANDA_CAN_MSG_INTERNAL *in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(buff + i); - PANDA_CAN_MSG in_msg; - - in_msg.addr_29b = (bool)(in_msg_raw->rir & CAN_EXTENDED); - in_msg.addr = (in_msg.addr_29b) ? (in_msg_raw->rir >> 3) : (in_msg_raw->rir >> 21); - in_msg.recv_time = this->runningTime.getTimePassedUS(); - in_msg.recv_time_point = std::chrono::steady_clock::now(); - //The timestamp from the device is (in_msg_raw->f2 >> 16), - //but this 16 bit value is a little hard to use. Using a - //timer since the initialization of this device. - in_msg.len = in_msg_raw->f2 & 0xF; - memcpy(in_msg.dat, in_msg_raw->dat, 8); - - in_msg.is_receipt = ((in_msg_raw->f2 >> 4) & 0x80) == 0x80; - switch ((in_msg_raw->f2 >> 4) & 0x7F) { - case PANDA_CAN1: - in_msg.bus = PANDA_CAN1; - break; - case PANDA_CAN2: - in_msg.bus = PANDA_CAN2; - break; - case PANDA_CAN3: - in_msg.bus = PANDA_CAN3; - break; - default: - in_msg.bus = PANDA_CAN_UNK; - } - msg_recv.push_back(in_msg); +PANDA_CAN_MSG Panda::parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw) { + PANDA_CAN_MSG in_msg; + + in_msg.addr_29b = (bool)(in_msg_raw->rir & CAN_EXTENDED); + in_msg.addr = (in_msg.addr_29b) ? (in_msg_raw->rir >> 3) : (in_msg_raw->rir >> 21); + in_msg.recv_time = this->runningTime.getTimePassedUS(); + in_msg.recv_time_point = std::chrono::steady_clock::now(); + //The timestamp from the device is (in_msg_raw->f2 >> 16), + //but this 16 bit value is a little hard to use. Using a + //timer since the initialization of this device. + in_msg.len = in_msg_raw->f2 & 0xF; + memcpy(in_msg.dat, in_msg_raw->dat, 8); + + in_msg.is_receipt = ((in_msg_raw->f2 >> 4) & 0x80) == 0x80; + switch ((in_msg_raw->f2 >> 4) & 0x7F) { + case PANDA_CAN1: + in_msg.bus = PANDA_CAN1; + break; + case PANDA_CAN2: + in_msg.bus = PANDA_CAN2; + break; + case PANDA_CAN3: + in_msg.bus = PANDA_CAN3; + break; + default: + in_msg.bus = PANDA_CAN_UNK; } + return in_msg; } -bool Panda::can_recv_async(HANDLE kill_event, std::vector& msg_buff, DWORD timeoutms) { - int retcount; - char buff[sizeof(PANDA_CAN_MSG_INTERNAL) * 4]; +bool Panda::can_rx_q_push(HANDLE kill_event, DWORD timeoutms) { + while (1) { + auto w_ptr = this->w_ptr; + auto n_ptr = w_ptr + 1; + if (n_ptr == CAN_RX_QUEUE_LEN) { + n_ptr = 0; + } + + // Pause if there is not a slot available in the queue + if (n_ptr == this->r_ptr) { + printf("RX queue full!\n"); + Sleep(1); + continue; + } - // Overlapped structure required for async read. - HANDLE m_hReadFinishedEvent = CreateEvent(NULL, TRUE, TRUE, NULL); - OVERLAPPED m_overlappedData; - memset(&m_overlappedData, sizeof(OVERLAPPED), 0); - m_overlappedData.hEvent = m_hReadFinishedEvent; + if (this->can_rx_q[n_ptr].complete) { + // TODO: is ResetEvent() faster? + CloseHandle(this->can_rx_q[n_ptr].complete); + } - HANDLE phSignals[2] = { m_hReadFinishedEvent, kill_event }; + // Overlapped structure required for async read. + this->can_rx_q[n_ptr].complete = CreateEvent(NULL, TRUE, TRUE, NULL); + memset(&this->can_rx_q[n_ptr].overlapped, sizeof(OVERLAPPED), 0); + this->can_rx_q[n_ptr].overlapped.hEvent = this->can_rx_q[n_ptr].complete; + this->can_rx_q[n_ptr].error = 0; - if (!WinUsb_ReadPipe(this->usbh, 0x81, (PUCHAR)buff, sizeof(buff), (PULONG)&retcount, &m_overlappedData)) { - // An overlapped read will return true if done, or false with an - // error of ERROR_IO_PENDING if the transfer is still in process. - DWORD dwError = GetLastError(); - if (dwError == ERROR_IO_PENDING) { - dwError = WaitForMultipleObjects(kill_event ? 2 : 1, phSignals, FALSE, timeoutms); + if (!WinUsb_ReadPipe(this->usbh, 0x81, this->can_rx_q[n_ptr].data, sizeof(this->can_rx_q[n_ptr].data), &this->can_rx_q[n_ptr].count, &this->can_rx_q[n_ptr].overlapped)) { + // An overlapped read will return true if done, or false with an + // error of ERROR_IO_PENDING if the transfer is still in process. + this->can_rx_q[n_ptr].error = GetLastError(); + } + + // Process the pipe read call from the previous invocation of this function + if (this->can_rx_q[w_ptr].error == ERROR_IO_PENDING) { + HANDLE phSignals[2] = { this->can_rx_q[w_ptr].complete, kill_event }; + auto dwError = WaitForMultipleObjects(kill_event ? 2 : 1, phSignals, FALSE, timeoutms); // Check if packet, timeout (nope), or break if (dwError == WAIT_OBJECT_0) { // Signal came from our usb object. Read the returned data. - if (!GetOverlappedResult(this->usbh, &m_overlappedData, (PULONG)&retcount, FALSE)) { + if (!GetOverlappedResult(this->usbh, &this->can_rx_q[w_ptr].overlapped, &this->can_rx_q[w_ptr].count, TRUE)) { // TODO: handle other error cases better. dwError = GetLastError(); printf("Got overlap error %d\n", dwError); - return TRUE; + continue; } - } else { + } + else { WinUsb_AbortPipe(this->usbh, 0x81); // Return FALSE to show that the optional signal @@ -422,17 +438,40 @@ bool Panda::can_recv_async(HANDLE kill_event, std::vector& msg_bu if (dwError == (WAIT_OBJECT_0 + 1)) { return FALSE; } - return TRUE; + continue; } - } else { // ERROR_BAD_COMMAND happens when device is unplugged. + } + else if (this->can_rx_q[w_ptr].error != 0) { // ERROR_BAD_COMMAND happens when device is unplugged. return FALSE; } + + this->w_ptr = n_ptr; } - parse_can_recv(msg_buff, buff, retcount); return TRUE; } +void Panda::can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count) { + count = 0; + + // No data left in queue + if (this->r_ptr == this->w_ptr) { + Sleep(1); + return; + } + + auto r_ptr = this->r_ptr; + for (int i = 0; i < this->can_rx_q[r_ptr].count; i += sizeof(PANDA_CAN_MSG_INTERNAL)) { + auto in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(this->can_rx_q[r_ptr].data + i); + msg_out[count] = parse_can_recv(in_msg_raw); + ++count; + } + + // Advance read pointer (wrap around if needed) + ++r_ptr; + this->r_ptr = (r_ptr == CAN_RX_QUEUE_LEN ? 0 : r_ptr); +} + std::vector Panda::can_recv() { std::vector msg_recv; int retcount; @@ -441,7 +480,11 @@ std::vector Panda::can_recv() { if (this->bulk_read(0x81, buff, sizeof(buff), (PULONG)&retcount, 0) == FALSE) return msg_recv; - parse_can_recv(msg_recv, buff, retcount); + for (int i = 0; i < retcount; i += sizeof(PANDA_CAN_MSG_INTERNAL)) { + PANDA_CAN_MSG_INTERNAL *in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(buff + i); + auto in_msg = parse_can_recv(in_msg_raw); + msg_recv.push_back(in_msg); + } return msg_recv; } diff --git a/panda/drivers/windows/panda/panda.h b/panda/drivers/windows/panda_shared/panda.h similarity index 87% rename from panda/drivers/windows/panda/panda.h rename to panda/drivers/windows/panda_shared/panda.h index 12a4fbb3184ba2..ade8fa36a8601e 100644 --- a/panda/drivers/windows/panda/panda.h +++ b/panda/drivers/windows/panda_shared/panda.h @@ -9,7 +9,7 @@ #ifdef PANDA_EXPORTS #define PANDA_API __declspec(dllexport) #else -#define PANDA_API __declspec(dllimport) +#define PANDA_API #endif #include @@ -31,6 +31,8 @@ #endif #define LIN_MSG_MAX_LEN 10 +#define CAN_RX_QUEUE_LEN 10000 +#define CAN_RX_MSG_LEN 1000 //template class __declspec(dllexport) std::basic_string; @@ -139,6 +141,7 @@ namespace panda { std::string get_usb_sn(); bool set_alt_setting(UCHAR alt_setting); UCHAR get_current_alt_setting(); + bool Panda::set_raw_io(bool val); PANDA_HEALTH get_health(); bool enter_bootloader(); @@ -160,9 +163,9 @@ namespace panda { bool can_send_many(const std::vector& can_msgs); bool can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t len, PANDA_CAN_PORT bus); - void parse_can_recv(std::vector& msg_recv, char *buff, int retcount); - bool can_recv_async(HANDLE kill_event, std::vector& msg_buff, DWORD timeoutms = INFINITE); std::vector can_recv(); + bool can_rx_q_push(HANDLE kill_event, DWORD timeoutms = INFINITE); + void can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count); bool can_clear(PANDA_CAN_PORT_CLEAR bus); std::string serial_read(PANDA_SERIAL_PORT port_number); @@ -202,6 +205,23 @@ namespace panda { ULONG timeout ); + #pragma pack(1) + typedef struct _PANDA_CAN_MSG_INTERNAL { + uint32_t rir; + uint32_t f2; + uint8_t dat[8]; + } PANDA_CAN_MSG_INTERNAL; + + typedef struct _CAN_RX_PIPE_READ { + unsigned char data[sizeof(PANDA_CAN_MSG_INTERNAL) * CAN_RX_MSG_LEN]; + unsigned long count; + OVERLAPPED overlapped; + HANDLE complete; + DWORD error; + } CAN_RX_PIPE_READ; + + PANDA_CAN_MSG parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw); + WINUSB_INTERFACE_HANDLE usbh; HANDLE devh; tstring devPath; @@ -209,6 +229,9 @@ namespace panda { bool loopback; Timer runningTime; + CAN_RX_PIPE_READ can_rx_q[CAN_RX_QUEUE_LEN]; + unsigned long w_ptr = 0; + unsigned long r_ptr = 0; }; } diff --git a/panda/drivers/windows/panda_shared/panda_shared.vcxitems b/panda/drivers/windows/panda_shared/panda_shared.vcxitems new file mode 100644 index 00000000000000..3f3b4765c0225c --- /dev/null +++ b/panda/drivers/windows/panda_shared/panda_shared.vcxitems @@ -0,0 +1,25 @@ + + + + $(MSBuildAllProjects);$(MSBuildThisFileFullPath) + true + {0c843279-68c7-4679-ae51-9bc463d50d1c} + + + + %(AdditionalIncludeDirectories);$(MSBuildThisFileDirectory) + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda/targetver.h b/panda/drivers/windows/panda_shared/targetver.h similarity index 100% rename from panda/drivers/windows/panda/targetver.h rename to panda/drivers/windows/panda_shared/targetver.h diff --git a/panda/examples/can_bit_transition.md b/panda/examples/can_bit_transition.md new file mode 100644 index 00000000000000..fa0a6c6bb354fd --- /dev/null +++ b/panda/examples/can_bit_transition.md @@ -0,0 +1,25 @@ +# How to use can_bit_transition.py to reverse engineer a single bit field + +Let's say our goal is to find a brake pedal signal (caused by your foot pressing the brake pedal vs adaptive cruise control braking). + +The following process will allow you to quickly find bits that are always 0 during a period of time (when you know you were not pressing the brake with your foot) and always 1 in a different period of time (when you know you were pressing the brake with your foot). + +Open up a drive in cabana where you can find a place you used the brake pedal and another place where you did not use the brake pedal (and you can identify when you were on the brake pedal and when you were not). You may want to go out for a drive and put something in front of the camera after you put your foot on the brake and take it away before you take your foot off the brake so you can easily identify exactly when you had your foot on the brake based on the video in cabana. This is critical because this script needs the brake signal to always be high the entire time for one of the time frames. A 10 second time frame worked well for me. + +I found a drive where I knew I was not pressing the brake between timestamp 50.0 thru 65.0 and I was pressing the brake between timestamp 69.0 thru 79.0. Determine what the timestamps are in cabana by plotting any message and putting your mouse over the plot at the location you want to discover the timestamp. The tool tip on mouse hover has the format: timestamp: value + +Now download the log from cabana (Save Log button) and run the script passing in the timestamps +(replace csv file name with cabana log you downloaded and time ranges with your own) +``` +./can_bit_transition.py ./honda_crv_ex_2017_can-1520354796875.csv 50.0-65.0 69.0-79.0 +``` + +The script will output bits that were always low in the first time range and always high in the second time range (and vice versa) +``` +id 17c 0 -> 1 at byte 4 bitmask 1 +id 17c 0 -> 1 at byte 6 bitmask 32 +id 221 1 -> 0 at byte 0 bitmask 4 +id 1be 0 -> 1 at byte 0 bitmask 16 +``` + +Now I go back to cabana and graph the above bits by searching for the message by id, double clicking on the appropriate bit, and then selecting "show plot". I already knew that message id 0x17c is both user brake and adaptive cruise control braking combined, so I plotted one of those signals along side 0x221 and 0x1be. By replaying a drive I could see that 0x221 was not a brake signal (when high at random times that did not correspond to braking). Next I looked at 0x1be and I found it was the brake pedal signal I was looking for (went high whenever I pressed the brake pedal and did not go high when adaptive cruise control was braking). \ No newline at end of file diff --git a/panda/examples/can_bit_transition.py b/panda/examples/can_bit_transition.py new file mode 100755 index 00000000000000..5c15e4bbc26eed --- /dev/null +++ b/panda/examples/can_bit_transition.py @@ -0,0 +1,87 @@ +#!/usr/bin/env python + +import binascii +import csv +import sys + +class Message(): + """Details about a specific message ID.""" + def __init__(self, message_id): + self.message_id = message_id + self.ones = [0] * 8 # bit set if 1 is always seen + self.zeros = [0] * 8 # bit set if 0 is always seen + + def printBitDiff(self, other): + """Prints bits that transition from always zero to always 1 and vice versa.""" + for i in xrange(len(self.ones)): + zero_to_one = other.zeros[i] & self.ones[i] + if zero_to_one: + print 'id %s 0 -> 1 at byte %d bitmask %d' % (self.message_id, i, zero_to_one) + one_to_zero = other.ones[i] & self.zeros[i] + if one_to_zero: + print 'id %s 1 -> 0 at byte %d bitmask %d' % (self.message_id, i, one_to_zero) + + +class Info(): + """A collection of Messages.""" + + def __init__(self): + self.messages = {} # keyed by MessageID + + def load(self, filename, start, end): + """Given a CSV file, adds information about message IDs and their values.""" + with open(filename, 'rb') as input: + reader = csv.reader(input) + next(reader, None) # skip the CSV header + for row in reader: + if not len(row): continue + time = float(row[0]) + bus = int(row[2]) + if time < start or bus > 127: + continue + elif time > end: + break + if row[1].startswith('0x'): + message_id = row[1][2:] # remove leading '0x' + else: + message_id = hex(int(row[1]))[2:] # old message IDs are in decimal + message_id = '%s:%s' % (bus, message_id) + if row[3].startswith('0x'): + data = row[3][2:] # remove leading '0x' + else: + data = row[3] + new_message = False + if message_id not in self.messages: + self.messages[message_id] = Message(message_id) + new_message = True + message = self.messages[message_id] + bytes = bytearray.fromhex(data) + for i in xrange(len(bytes)): + ones = int(bytes[i]) + message.ones[i] = ones if new_message else message.ones[i] & ones + # Inverts the data and masks it to a byte to get the zeros as ones. + zeros = (~int(bytes[i])) & 0xff + message.zeros[i] = zeros if new_message else message.zeros[i] & zeros + +def PrintUnique(log_file, low_range, high_range): + # find messages with bits that are always low + start, end = map(float, low_range.split('-')) + low = Info() + low.load(log_file, start, end) + # find messages with bits that are always high + start, end = map(float, high_range.split('-')) + high = Info() + high.load(log_file, start, end) + # print messages that go from low to high + found = False + for message_id in sorted(high.messages): + if message_id in low.messages: + high.messages[message_id].printBitDiff(low.messages[message_id]) + found = True + if not found: print 'No messages that transition from always low to always high found!' + +if __name__ == "__main__": + if len(sys.argv) < 4: + print 'Usage:\n%s log.csv - -' % sys.argv[0] + sys.exit(0) + PrintUnique(sys.argv[1], sys.argv[2], sys.argv[3]) diff --git a/panda/examples/can_unique.py b/panda/examples/can_unique.py index 42488c64bb24fd..ad6de296ee4174 100755 --- a/panda/examples/can_unique.py +++ b/panda/examples/can_unique.py @@ -51,10 +51,12 @@ def load(self, filename): reader = csv.reader(input) next(reader, None) # skip the CSV header for row in reader: + bus = row[0] if row[1].startswith('0x'): message_id = row[1][2:] # remove leading '0x' else: message_id = hex(int(row[1]))[2:] # old message IDs are in decimal + message_id = '%s:%s' % (bus, message_id) if row[1].startswith('0x'): data = row[2][2:] # remove leading '0x' else: @@ -76,7 +78,7 @@ def PrintUnique(interesting_file, background_files): background.load(background_file) interesting = Info() interesting.load(interesting_file) - for message_id in interesting.messages: + for message_id in sorted(interesting.messages): if message_id not in background.messages: print 'New message_id: %s' % message_id else: diff --git a/panda/examples/get_panda_password.py b/panda/examples/get_panda_password.py new file mode 100644 index 00000000000000..11071d035346be --- /dev/null +++ b/panda/examples/get_panda_password.py @@ -0,0 +1,20 @@ +#!/usr/bin/env python +from panda import Panda + +def get_panda_password(): + + try: + print("Trying to connect to Panda over USB...") + p = Panda() + + except AssertionError: + print("USB connection failed") + sys.exit(0) + + wifi = p.get_serial() + #print('[%s]' % ', '.join(map(str, wifi))) + print("SSID: " + wifi[0]) + print("Password: " + wifi[1]) + +if __name__ == "__main__": + get_panda_password() \ No newline at end of file diff --git a/panda/examples/isotp.py b/panda/examples/isotp.py deleted file mode 100644 index 8d7a98e773aaf2..00000000000000 --- a/panda/examples/isotp.py +++ /dev/null @@ -1,77 +0,0 @@ -DEBUG = False - -def msg(x): - if DEBUG: - print "S:",x.encode("hex") - if len(x) <= 7: - ret = chr(len(x)) + x - else: - assert False - return ret.ljust(8, "\x00") - -def isotp_send(panda, x, addr, bus=0): - if len(x) <= 7: - panda.can_send(addr, msg(x), bus) - else: - ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6] - x = x[6:] - idx = 1 - sends = [] - while len(x) > 0: - sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\x00"))) - x = x[7:] - idx += 1 - - # actually send - panda.can_send(addr, ss, bus) - rr = recv(panda, 1, addr+8, bus)[0] - panda.can_send_many([(addr, None, s, 0) for s in sends]) - -kmsgs = [] -def recv(panda, cnt, addr, nbus): - global kmsgs - ret = [] - - while len(ret) < cnt: - kmsgs += panda.can_recv() - nmsgs = [] - for ids, ts, dat, bus in kmsgs: - if ids == addr and bus == nbus and len(ret) < cnt: - ret.append(dat) - else: - pass - kmsgs = nmsgs - return map(str, ret) - -def isotp_recv(panda, addr, bus=0): - msg = recv(panda, 1, addr, bus)[0] - - if ord(msg[0])&0xf0 == 0x10: - # first - tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1]) - dat = msg[2:] - - # 0 block size? - CONTINUE = "\x30" + "\x00"*7 - - panda.can_send(addr-8, CONTINUE, bus) - - idx = 1 - for mm in recv(panda, (tlen-len(dat) + 7)/8, addr, bus): - assert ord(mm[0]) == (0x20 | idx) - dat += mm[1:] - idx += 1 - elif ord(msg[0])&0xf0 == 0x00: - # single - tlen = ord(msg[0]) & 0xf - dat = msg[1:] - else: - assert False - - dat = dat[0:tlen] - - if DEBUG: - print "R:",dat.encode("hex") - - return dat - diff --git a/panda/examples/tesla_tester.py b/panda/examples/tesla_tester.py index b2cbb4d789e18d..99d8d92854423b 100644 --- a/panda/examples/tesla_tester.py +++ b/panda/examples/tesla_tester.py @@ -29,11 +29,11 @@ def tesla_tester(): # BDY 0x248 is the MCU_commands message, which includes folding mirrors, opening the trunk, frunk, setting the cars lock state and more. For our test, we will edit the 3rd byte, which is MCU_lockRequest. 0x01 will lock, 0x02 will unlock: print("Unlocking Tesla...") - p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", bus_num) + p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", body_bus_num) #Or, we can set the first byte, MCU_frontHoodCommand + MCU_liftgateSwitch, to 0x01 to pop the frunk, or 0x04 to open/close the trunk (0x05 should open both) print("Opening Frunk...") - p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", bus_num) + p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", body_bus_num) #Back to safety... print("Disabling output on Panda...") @@ -41,7 +41,6 @@ def tesla_tester(): print("Reading VIN from 0x568. This is painfully slow and can take up to 3 minutes (1 minute per message; 3 messages needed for full VIN)...") - cnt = 0 vin = {} while True: #Read the VIN @@ -53,11 +52,10 @@ def tesla_tester(): vin_string = binascii.hexlify(dat)[2:] #rest of the string is the actual VIN data vin[vin_index] = vin_string.decode("hex") print("Got VIN index " + str(vin_index) + " data " + vin[vin_index]) - cnt += 1 #if we have all 3 parts of the VIN, print it and break out of our while loop - if cnt == 3: + if 0 in vin and 1 in vin and 2 in vin: print("VIN: " + vin[0] + vin[1] + vin[2][:3]) break if __name__ == "__main__": - tesla_tester() \ No newline at end of file + tesla_tester() diff --git a/panda/panda.png b/panda/panda.png index f37175d9e58df9..e18137d8727c0f 100644 Binary files a/panda/panda.png and b/panda/panda.png differ diff --git a/panda/python/__init__.py b/panda/python/__init__.py index 95a2b89d24bd85..c49ee83622f523 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -12,11 +12,15 @@ from esptool import ESPROM, CesantaFlasher from flash_release import flash_release from update import ensure_st_up_to_date +from serial import PandaSerial +from isotp import isotp_send, isotp_recv -__version__ = '0.0.6' +__version__ = '0.0.8' BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") +DEBUG = os.getenv("PANDADEBUG") is not None + # *** wifi mode *** def build_st(target, mkfile="Makefile"): @@ -33,7 +37,10 @@ def parse_can_buffer(dat): address = f1 >> 3 else: address = f1 >> 21 - ret.append((address, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xFF)) + dddat = ddat[8:8+(f2&0xF)] + if DEBUG: + print(" R %x: %s" % (address, str(dddat).encode("hex"))) + ret.append((address, f2>>16, dddat, (f2>>4)&0xFF)) return ret class PandaWifiStreaming(object): @@ -98,6 +105,14 @@ class Panda(object): SAFETY_NOOUTPUT = 0 SAFETY_HONDA = 1 SAFETY_TOYOTA = 2 + SAFETY_GM = 3 + SAFETY_HONDA_BOSCH = 4 + SAFETY_FORD = 5 + SAFETY_CADILLAC = 6 + SAFETY_HYUNDAI = 7 + SAFETY_TESLA = 8 + SAFETY_CHRYSLER = 9 + SAFETY_TOYOTA_IPAS = 0x1335 SAFETY_TOYOTA_NOLIMITS = 0x1336 SAFETY_ALLOUTPUT = 0x1337 SAFETY_ELM327 = 0xE327 @@ -147,6 +162,7 @@ def connect(self, claim=True, wait=False): if self._serial is None or this_serial == self._serial: self._serial = this_serial print("opening device", self._serial, hex(device.getProductID())) + time.sleep(1) self.bootstub = device.getProductID() == 0xddee self.legacy = (device.getbcdDevice() != 0x2300) self._handle = device.open() @@ -175,27 +191,58 @@ def reset(self, enter_bootstub=False, enter_bootloader=False): except Exception: pass if not enter_bootloader: - self.close() - time.sleep(1.0) - success = False - # wait up to 15 seconds - for i in range(0, 15): + self.reconnect() + + def reconnect(self): + self.close() + time.sleep(1.0) + success = False + # wait up to 15 seconds + for i in range(0, 15): + try: + self.connect() + success = True + break + except Exception: + print("reconnecting is taking %d seconds..." % (i+1)) try: - self.connect() - success = True - break + dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial)) + dfu.recover() except Exception: - print("reconnecting is taking %d seconds..." % (i+1)) - try: - dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial)) - dfu.recover() - except Exception: - pass - time.sleep(1.0) - if not success: - raise Exception("reset failed") + pass + time.sleep(1.0) + if not success: + raise Exception("reconnect failed") + + @staticmethod + def flash_static(handle, code): + # confirm flasher is present + fr = handle.controlRead(Panda.REQUEST_IN, 0xb0, 0, 0, 0xc) + assert fr[4:8] == "\xde\xad\xd0\x0d" + + # unlock flash + print("flash: unlocking") + handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'') + + # erase sectors 1 and 2 + print("flash: erasing") + handle.controlWrite(Panda.REQUEST_IN, 0xb2, 1, 0, b'') + handle.controlWrite(Panda.REQUEST_IN, 0xb2, 2, 0, b'') + + # flash over EP2 + STEP = 0x10 + print("flash: flashing") + for i in range(0, len(code), STEP): + handle.bulkWrite(2, code[i:i+STEP]) + + # reset + print("flash: resetting") + try: + handle.controlWrite(Panda.REQUEST_IN, 0xd8, 0, 0, b'') + except Exception: + pass - def flash(self, fn=None, code=None): + def flash(self, fn=None, code=None, reconnect=True): if not self.bootstub: self.reset(enter_bootstub=True) assert(self.bootstub) @@ -218,28 +265,12 @@ def flash(self, fn=None, code=None): # get version print("flash: version is "+self.get_version()) - # confirm flasher is present - fr = self._handle.controlRead(Panda.REQUEST_IN, 0xb0, 0, 0, 0xc) - assert fr[4:8] == "\xde\xad\xd0\x0d" - - # unlock flash - print("flash: unlocking") - self._handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'') - - # erase sectors 1 and 2 - print("flash: erasing") - self._handle.controlWrite(Panda.REQUEST_IN, 0xb2, 1, 0, b'') - self._handle.controlWrite(Panda.REQUEST_IN, 0xb2, 2, 0, b'') - - # flash over EP2 - STEP = 0x10 - print("flash: flashing") - for i in range(0, len(code), STEP): - self._handle.bulkWrite(2, code[i:i+STEP]) + # do flash + Panda.flash_static(self._handle, code) - # reset - print("flash: resetting") - self.reset() + # reconnect + if reconnect: + self.reconnect() def recover(self): self.reset(enter_bootloader=True) @@ -309,6 +340,10 @@ def enter_bootloader(self): def get_version(self): return self._handle.controlRead(Panda.REQUEST_IN, 0xd6, 0, 0, 0x40) + def is_grey(self): + ret = self._handle.controlRead(Panda.REQUEST_IN, 0xc1, 0, 0, 0x40) + return ret == "\x01" + def get_serial(self): dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20) hashsig, calc_hash = dat[0x1c:], hashlib.sha1(dat[0:0x1c]).digest()[0:4] @@ -368,6 +403,8 @@ def can_send_many(self, arr): extended = 4 for addr, _, dat, bus in arr: assert len(dat) <= 8 + if DEBUG: + print(" W %x: %s" % (addr, dat.encode("hex"))) if addr >= 0x800: rir = (addr << 3) | transmit | extended else: @@ -412,6 +449,14 @@ def can_clear(self, bus): """ self._handle.controlWrite(Panda.REQUEST_OUT, 0xf1, bus, 0, b'') + # ******************* isotp ******************* + + def isotp_send(self, addr, dat, bus, recvaddr=None, subaddr=None): + return isotp_send(self, dat, addr, bus, recvaddr, subaddr) + + def isotp_recv(self, addr, bus=0, sendaddr=None, subaddr=None): + return isotp_recv(self, addr, bus, sendaddr, subaddr) + # ******************* serial ******************* def serial_read(self, port_number): @@ -424,7 +469,10 @@ def serial_read(self, port_number): return b''.join(ret) def serial_write(self, port_number, ln): - return self._handle.bulkWrite(2, struct.pack("B", port_number) + ln) + ret = 0 + for i in range(0, len(ln), 0x20): + ret += self._handle.bulkWrite(2, struct.pack("B", port_number) + ln[i:i+0x20]) + return ret def serial_clear(self, port_number): """Clears all messages (tx and rx) from the specified internal uart @@ -440,7 +488,11 @@ def serial_clear(self, port_number): # pulse low for wakeup def kline_wakeup(self): + if DEBUG: + print("kline wakeup...") self._handle.controlWrite(Panda.REQUEST_OUT, 0xf0, 0, 0, b'') + if DEBUG: + print("kline wakeup done") def kline_drain(self, bus=2): # drain buffer @@ -449,19 +501,25 @@ def kline_drain(self, bus=2): ret = self._handle.controlRead(Panda.REQUEST_IN, 0xe0, bus, 0, 0x40) if len(ret) == 0: break + elif DEBUG: + print("kline drain: "+str(ret).encode("hex")) bret += ret return bytes(bret) def kline_ll_recv(self, cnt, bus=2): echo = bytearray() while len(echo) != cnt: - echo += self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo)) - return echo + ret = str(self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo))) + if DEBUG and len(ret) > 0: + print("kline recv: "+ret.encode("hex")) + echo += ret + return str(echo) def kline_send(self, x, bus=2, checksum=True): def get_checksum(dat): result = 0 result += sum(map(ord, dat)) if isinstance(b'dat', str) else sum(dat) + result = -result return struct.pack("B", result % 0x100) self.kline_drain(bus=bus) @@ -469,6 +527,8 @@ def get_checksum(dat): x += get_checksum(x) for i in range(0, len(x), 0xf): ts = x[i:i+0xf] + if DEBUG: + print("kline send: "+ts.encode("hex")) self._handle.bulkWrite(2, chr(bus).encode()+ts) echo = self.kline_ll_recv(len(ts), bus=bus) if echo != ts: diff --git a/panda/python/isotp.py b/panda/python/isotp.py new file mode 100644 index 00000000000000..d68aa4d70e0bbe --- /dev/null +++ b/panda/python/isotp.py @@ -0,0 +1,135 @@ +DEBUG = False + +def msg(x): + if DEBUG: + print "S:",x.encode("hex") + if len(x) <= 7: + ret = chr(len(x)) + x + else: + assert False + return ret.ljust(8, "\x00") + +kmsgs = [] +def recv(panda, cnt, addr, nbus): + global kmsgs + ret = [] + + while len(ret) < cnt: + kmsgs += panda.can_recv() + nmsgs = [] + for ids, ts, dat, bus in kmsgs: + if ids == addr and bus == nbus and len(ret) < cnt: + ret.append(dat) + else: + # leave around + nmsgs.append((ids, ts, dat, bus)) + kmsgs = nmsgs[-256:] + return map(str, ret) + +def isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr): + msg = recv(panda, 1, addr, bus)[0] + + # TODO: handle other subaddr also communicating + assert ord(msg[0]) == subaddr + + if ord(msg[1])&0xf0 == 0x10: + # first + tlen = ((ord(msg[1]) & 0xf) << 8) | ord(msg[2]) + dat = msg[3:] + + # 0 block size? + CONTINUE = chr(subaddr) + "\x30" + "\x00"*6 + panda.can_send(sendaddr, CONTINUE, bus) + + idx = 1 + for mm in recv(panda, (tlen-len(dat) + 5)/6, addr, bus): + assert ord(mm[0]) == subaddr + assert ord(mm[1]) == (0x20 | (idx&0xF)) + dat += mm[2:] + idx += 1 + elif ord(msg[1])&0xf0 == 0x00: + # single + tlen = ord(msg[1]) & 0xf + dat = msg[2:] + else: + print msg.encode("hex") + assert False + + return dat[0:tlen] + +# **** import below this line **** + +def isotp_send(panda, x, addr, bus=0, recvaddr=None, subaddr=None): + if recvaddr is None: + recvaddr = addr+8 + + if len(x) <= 7 and subaddr is None: + panda.can_send(addr, msg(x), bus) + elif len(x) <= 6 and subaddr is not None: + panda.can_send(addr, chr(subaddr)+msg(x)[0:7], bus) + else: + if subaddr: + ss = chr(subaddr) + chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:5] + x = x[5:] + else: + ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6] + x = x[6:] + idx = 1 + sends = [] + while len(x) > 0: + if subaddr: + sends.append(((chr(subaddr) + chr(0x20 + (idx&0xF)) + x[0:6]).ljust(8, "\x00"))) + x = x[6:] + else: + sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\x00"))) + x = x[7:] + idx += 1 + + # actually send + panda.can_send(addr, ss, bus) + rr = recv(panda, 1, recvaddr, bus)[0] + if rr.find("\x30\x01") != -1: + for s in sends[:-1]: + panda.can_send(addr, s, 0) + rr = recv(panda, 1, recvaddr, bus)[0] + panda.can_send(addr, sends[-1], 0) + else: + panda.can_send_many([(addr, None, s, 0) for s in sends]) + +def isotp_recv(panda, addr, bus=0, sendaddr=None, subaddr=None): + if sendaddr is None: + sendaddr = addr-8 + + if subaddr is not None: + dat = isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr) + else: + msg = recv(panda, 1, addr, bus)[0] + + if ord(msg[0])&0xf0 == 0x10: + # first + tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1]) + dat = msg[2:] + + # 0 block size? + CONTINUE = "\x30" + "\x00"*7 + + panda.can_send(sendaddr, CONTINUE, bus) + + idx = 1 + for mm in recv(panda, (tlen-len(dat) + 6)/7, addr, bus): + assert ord(mm[0]) == (0x20 | (idx&0xF)) + dat += mm[1:] + idx += 1 + elif ord(msg[0])&0xf0 == 0x00: + # single + tlen = ord(msg[0]) & 0xf + dat = msg[1:] + else: + assert False + dat = dat[0:tlen] + + if DEBUG: + print "R:",dat.encode("hex") + + return dat + diff --git a/panda/python/serial.py b/panda/python/serial.py new file mode 100644 index 00000000000000..1bcfebb32eabd0 --- /dev/null +++ b/panda/python/serial.py @@ -0,0 +1,27 @@ +# mimic a python serial port +class PandaSerial(object): + def __init__(self, panda, port, baud): + self.panda = panda + self.port = port + self.panda.set_uart_parity(self.port, 0) + self.panda.set_uart_baud(self.port, baud) + self.buf = "" + + def read(self, l=1): + tt = self.panda.serial_read(self.port) + if len(tt) > 0: + #print "R: ", tt.encode("hex") + self.buf += tt + ret = self.buf[0:l] + self.buf = self.buf[l:] + return ret + + def write(self, dat): + #print "W: ", dat.encode("hex") + #print ' pigeon_send("' + ''.join(map(lambda x: "\\x%02X" % ord(x), dat)) + '");' + return self.panda.serial_write(self.port, dat) + + def close(self): + pass + + diff --git a/panda/tests/automated/helpers.py b/panda/tests/automated/helpers.py index daa676490d3342..1ddced117980ee 100644 --- a/panda/tests/automated/helpers.py +++ b/panda/tests/automated/helpers.py @@ -3,6 +3,7 @@ import time import random import subprocess +import requests from panda import Panda from nose.tools import timed, assert_equal, assert_less, assert_greater @@ -25,27 +26,46 @@ def connect_wifi(): assert(dongle_id.isalnum()) _connect_wifi(dongle_id, pw) -def _connect_wifi(dongle_id, pw): +def _connect_wifi(dongle_id, pw, insecure_okay=False): ssid = str("panda-" + dongle_id) print("WIFI: connecting to %s" % ssid) - if sys.platform == "darwin": - os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw)) - else: - cnt = 0 - MAX_TRIES = 10 - while cnt < MAX_TRIES: - print "WIFI: scanning %d" % cnt - os.system("nmcli device wifi rescan") - wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n")) - if len(wifi_scan) != 0: + while 1: + if sys.platform == "darwin": + os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw)) + else: + wlan_interface = subprocess.check_output(["sh", "-c", "iw dev | awk '/Interface/ {print $2}'"]).strip() + cnt = 0 + MAX_TRIES = 10 + while cnt < MAX_TRIES: + print "WIFI: scanning %d" % cnt + os.system("sudo iwlist %s scanning > /dev/null" % wlan_interface) + os.system("nmcli device wifi rescan") + wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n")) + if len(wifi_scan) != 0: + break + time.sleep(0.1) + # MAX_TRIES tries, ~10 seconds max + cnt += 1 + assert cnt < MAX_TRIES + if "-pair" in wifi_scan[0]: + os.system("nmcli d wifi connect %s-pair" % (ssid)) + if insecure_okay: + break + # fetch webpage + print "connecting to insecure network to secure" + r = requests.get("http://192.168.0.10/") + assert r.status_code==200 + + print "securing" + try: + r = requests.get("http://192.168.0.10/secure", timeout=0.01) + except requests.exceptions.Timeout: + pass + else: + os.system("nmcli d wifi connect %s password %s" % (ssid, pw)) break - time.sleep(0.1) - # MAX_TRIES tries, ~10 seconds max - cnt += 1 - assert cnt < MAX_TRIES - os.system("nmcli d wifi connect %s password %s" % (ssid, pw)) # TODO: confirm that it's connected to the right panda diff --git a/panda/tests/build/Dockerfile b/panda/tests/build/Dockerfile new file mode 100644 index 00000000000000..276a25ed0b9495 --- /dev/null +++ b/panda/tests/build/Dockerfile @@ -0,0 +1,17 @@ +FROM ubuntu:16.04 + +RUN apt-get update && apt-get install -y gcc-arm-none-eabi libnewlib-arm-none-eabi python python-pip gcc g++ git autoconf gperf bison flex automake texinfo wget help2man gawk libtool libtool-bin ncurses-dev unzip unrar-free libexpat-dev sed bzip2 + +RUN pip install pycrypto==2.6.1 + +# Build esp toolchain +RUN mkdir -p /panda/boardesp +WORKDIR /panda/boardesp +RUN git clone --recursive https://github.com/pfalcon/esp-open-sdk.git +WORKDIR /panda/boardesp/esp-open-sdk +RUN git checkout 03f5e898a059451ec5f3de30e7feff30455f7ce +RUN CT_ALLOW_BUILD_AS_ROOT_SURE=1 make STANDALONE=y + +COPY . /panda + +WORKDIR /panda diff --git a/panda/tests/can_printer.py b/panda/tests/can_printer.py index a74a548109269b..e863889c16424b 100755 --- a/panda/tests/can_printer.py +++ b/panda/tests/can_printer.py @@ -4,6 +4,7 @@ import sys import time from collections import defaultdict +import binascii sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) from panda import Panda @@ -14,6 +15,7 @@ def sec_since_boot(): def can_printer(): p = Panda() + p.set_safety_mode(0x1337) start = sec_since_boot() lp = sec_since_boot() @@ -28,7 +30,7 @@ def can_printer(): if sec_since_boot() - lp > 0.1: dd = chr(27) + "[2J" dd += "%5.2f\n" % (sec_since_boot() - start) - for k,v in sorted(zip(msgs.keys(), map(lambda x: x[-1].encode("hex"), msgs.values()))): + for k,v in sorted(zip(msgs.keys(), map(lambda x: binascii.hexlify(x[-1]), msgs.values()))): dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) print(dd) lp = sec_since_boot() diff --git a/panda/tests/automated/elm_wifi.py b/panda/tests/elm_wifi.py similarity index 100% rename from panda/tests/automated/elm_wifi.py rename to panda/tests/elm_wifi.py diff --git a/panda/tests/gmbitbang/recv.py b/panda/tests/gmbitbang/recv.py new file mode 100755 index 00000000000000..6eb70aa4ad3abb --- /dev/null +++ b/panda/tests/gmbitbang/recv.py @@ -0,0 +1,17 @@ +#!/usr/bin/env python +import time +from panda import Panda + +p = Panda() +p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) +p.set_gmlan(bus=2) +#p.can_send(0xaaa, "\x00\x00", bus=3) +last_add = None +while 1: + ret = p.can_recv() + if len(ret) > 0: + add = ret[0][0] + if last_add is not None and add != last_add+1: + print "MISS %d %d" % (last_add, add) + last_add = add + print ret diff --git a/panda/tests/gmbitbang/rigol.py b/panda/tests/gmbitbang/rigol.py new file mode 100755 index 00000000000000..3d690fdd84c725 --- /dev/null +++ b/panda/tests/gmbitbang/rigol.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python +import numpy as np +import visa +import matplotlib.pyplot as plt + +resources = visa.ResourceManager() +print resources.list_resources() + +scope = resources.open_resource('USB0::0x1AB1::0x04CE::DS1ZA184652242::INSTR', timeout=2000, chunk_size=1024000) +print(scope.query('*IDN?').strip()) + +#voltscale = scope.ask_for_values(':CHAN1:SCAL?')[0] +#voltoffset = scope.ask_for_values(":CHAN1:OFFS?")[0] + +#scope.write(":STOP") +scope.write(":WAV:POIN:MODE RAW") +scope.write(":WAV:DATA? CHAN1")[10:] +rawdata = scope.read_raw() +data = np.frombuffer(rawdata, 'B') +print data.shape + +s1 = data[0:650] +s2 = data[650:] +s1i = np.argmax(s1 > 100) +s2i = np.argmax(s2 > 100) +s1 = s1[s1i:] +s2 = s2[s2i:] + +plt.plot(s1) +plt.plot(s2) +plt.show() +#data = (data - 130.0 - voltoffset/voltscale*25) / 25 * voltscale + +print data + diff --git a/panda/tests/gmbitbang/test.py b/panda/tests/gmbitbang/test.py new file mode 100755 index 00000000000000..652ac1ddd8ad24 --- /dev/null +++ b/panda/tests/gmbitbang/test.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python +import time +from panda import Panda + +p1 = Panda('380016000551363338383037') +p2 = Panda('430026000951363338383037') + +# this is a test, no safety +p1.set_safety_mode(Panda.SAFETY_ALLOUTPUT) +p2.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + +# get versions +print(p1.get_version()) +print(p2.get_version()) + +# this sets bus 2 to actually be GMLAN +p2.set_gmlan(bus=2) + +# send w bitbang then without +#iden = 123 +iden = 18000 +#dat = "\x01\x02" +dat = "\x01\x02\x03\x04\x05\x06\x07\x08" +while 1: + iden += 1 + p1.set_gmlan(bus=None) + p1.can_send(iden, dat, bus=3) + #p1.set_gmlan(bus=2) + #p1.can_send(iden, dat, bus=3) + time.sleep(0.01) + print p2.can_recv() + #exit(0) + diff --git a/panda/tests/gmbitbang/test_one.py b/panda/tests/gmbitbang/test_one.py new file mode 100755 index 00000000000000..a398e2780385b1 --- /dev/null +++ b/panda/tests/gmbitbang/test_one.py @@ -0,0 +1,23 @@ +#!/usr/bin/env python +import time +from panda import Panda + +p = Panda() +p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + +# ack any crap on bus +p.set_gmlan(bus=2) +time.sleep(0.1) +while len(p.can_recv()) > 0: + print "clearing" + time.sleep(0.1) +print "cleared" +p.set_gmlan(bus=None) + +iden = 18000 +dat = "\x01\x02\x03\x04\x05\x06\x07\x08" +while 1: + iden += 1 + p.can_send(iden, dat, bus=3) + time.sleep(0.01) + diff --git a/panda/tests/gmbitbang/test_packer.c b/panda/tests/gmbitbang/test_packer.c new file mode 100644 index 00000000000000..f056dd48125d34 --- /dev/null +++ b/panda/tests/gmbitbang/test_packer.c @@ -0,0 +1,32 @@ +#include +#include + +typedef struct { + uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +#include "../../board/drivers/canbitbang.h" + +int main() { + char out[300]; + CAN_FIFOMailBox_TypeDef to_bang = {0}; + to_bang.RIR = 20 << 21; + to_bang.RDTR = 1; + to_bang.RDLR = 1; + + int len = get_bit_message(out, &to_bang); + printf("T:"); + for (int i = 0; i < len; i++) { + printf("%d", out[i]); + } + printf("\n"); + printf("R:0000010010100000100010000010011110111010100111111111111111"); + printf("\n"); + return 0; +} + + + diff --git a/panda/tests/location_listener.py b/panda/tests/location_listener.py new file mode 100755 index 00000000000000..cbbb00d794f5e3 --- /dev/null +++ b/panda/tests/location_listener.py @@ -0,0 +1,47 @@ +#!/usr/bin/env python +import os +import time +import sys + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda, PandaSerial + +def add_nmea_checksum(msg): + d = msg[1:] + cs = 0 + for i in d: + cs ^= ord(i) + return msg + "*%02X" % cs + +if __name__ == "__main__": + panda = Panda() + ser = PandaSerial(panda, 1, 9600) + + # power cycle by toggling reset + print "resetting" + panda.set_esp_power(0) + time.sleep(0.5) + panda.set_esp_power(1) + time.sleep(0.5) + print "done" + print ser.read(1024) + + # upping baud rate + baudrate = 460800 + + print "upping baud rate" + msg = add_nmea_checksum("$PUBX,41,1,0007,0003,%d,0" % baudrate)+"\r\n" + print msg + ser.write(msg) + time.sleep(0.1) # needs a wait for it to actually send + + # new panda serial + ser = PandaSerial(panda, 1, baudrate) + + while True: + ret = ser.read(1024) + if len(ret) > 0: + sys.stdout.write(ret) + sys.stdout.flush() + #print str(ret).encode("hex") + diff --git a/panda/tests/pedal/enter_canloader.py b/panda/tests/pedal/enter_canloader.py new file mode 100755 index 00000000000000..c6f06ca35499a0 --- /dev/null +++ b/panda/tests/pedal/enter_canloader.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python +import sys +import time +import struct +import argparse +import signal +from panda import Panda + +class CanHandle(object): + def __init__(self, p): + self.p = p + + def transact(self, dat): + #print "W:",dat.encode("hex") + self.p.isotp_send(1, dat, 0, recvaddr=2) + + def _handle_timeout(signum, frame): + # will happen on reset + raise Exception("timeout") + + signal.signal(signal.SIGALRM, _handle_timeout) + signal.alarm(1) + try: + ret = self.p.isotp_recv(2, 0, sendaddr=1) + finally: + signal.alarm(0) + + #print "R:",ret.encode("hex") + return ret + + def controlWrite(self, request_type, request, value, index, data, timeout=0): + # ignore data in reply, panda doesn't use it + return self.controlRead(request_type, request, value, index, 0, timeout) + + def controlRead(self, request_type, request, value, index, length, timeout=0): + dat = struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length) + return self.transact(dat) + + def bulkWrite(self, endpoint, data, timeout=0): + if len(data) > 0x10: + raise ValueError("Data must not be longer than 0x10") + dat = struct.pack("HH", endpoint, len(data))+data + return self.transact(dat) + + def bulkRead(self, endpoint, length, timeout=0): + dat = struct.pack("HH", endpoint, 0) + return self.transact(dat) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Flash pedal over can') + parser.add_argument('--recover', action='store_true') + parser.add_argument("fn", type=str, nargs='?', help="flash file") + args = parser.parse_args() + + p = Panda() + p.set_safety_mode(0x1337) + + while 1: + if len(p.can_recv()) == 0: + break + + if args.recover: + p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x02", 0) + exit(0) + else: + p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x0a", 0) + + if args.fn: + time.sleep(0.1) + print "flashing", args.fn + code = open(args.fn).read() + Panda.flash_static(CanHandle(p), code) + + print "can flash done" + + diff --git a/panda/tests/read_winusb_descriptors.py b/panda/tests/read_winusb_descriptors.py new file mode 100644 index 00000000000000..e38df8d1caa9c3 --- /dev/null +++ b/panda/tests/read_winusb_descriptors.py @@ -0,0 +1,29 @@ +#!/usr/bin/env python +from panda import Panda +from hexdump import hexdump + +DEBUG = False + +if __name__ == "__main__": + p = Panda() + + len = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, 1) + print 'Microsoft OS String Descriptor' + dat = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, len[0]) + if DEBUG: print 'LEN: {}'.format(hex(len[0])) + hexdump("".join(map(chr, dat))) + + ms_vendor_code = dat[16] + if DEBUG: print 'MS_VENDOR_CODE: {}'.format(hex(len[0])) + + print '\nMicrosoft Compatible ID Feature Descriptor' + len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, 1) + if DEBUG: print 'LEN: {}'.format(hex(len[0])) + dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, len[0]) + hexdump("".join(map(chr, dat))) + + print '\nMicrosoft Extended Properties Feature Descriptor' + len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, 1) + if DEBUG: print 'LEN: {}'.format(hex(len[0])) + dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, len[0]) + hexdump("".join(map(chr, dat))) diff --git a/panda/tests/safety/Dockerfile b/panda/tests/safety/Dockerfile new file mode 100644 index 00000000000000..9381fdc4085759 --- /dev/null +++ b/panda/tests/safety/Dockerfile @@ -0,0 +1,6 @@ +FROM ubuntu:16.04 + +RUN apt-get update && apt-get install -y clang make python python-pip +COPY tests/safety/requirements.txt /panda/tests/safety/requirements.txt +RUN pip install -r /panda/tests/safety/requirements.txt +COPY . /panda diff --git a/panda/tests/safety/Makefile b/panda/tests/safety/Makefile new file mode 100644 index 00000000000000..334a29427d7d29 --- /dev/null +++ b/panda/tests/safety/Makefile @@ -0,0 +1,18 @@ +CC = clang +CCFLAGS = -O3 -fPIC -DPANDA -I. + +.PHONY: all +all: libpandasafety.so + +libpandasafety.so: test.o + $(CC) -shared -o '$@' $^ -lm + +test.o: test.c + @echo "[ CC ] $@" + $(CC) $(CCFLAGS) -MMD -c -I../../board -o '$@' '$<' + +.PHONY: clean +clean: + rm -f libpandasafety.so test.o test.d + +-include test.d diff --git a/panda/tests/safety/libpandasafety_py.py b/panda/tests/safety/libpandasafety_py.py new file mode 100644 index 00000000000000..c6df9d3340a8a6 --- /dev/null +++ b/panda/tests/safety/libpandasafety_py.py @@ -0,0 +1,92 @@ +import os +import subprocess + +from cffi import FFI + +can_dir = os.path.dirname(os.path.abspath(__file__)) +libpandasafety_fn = os.path.join(can_dir, "libpandasafety.so") +subprocess.check_call(["make"], cwd=can_dir) + +ffi = FFI() +ffi.cdef(""" +typedef struct +{ + uint32_t TIR; /*!< CAN TX mailbox identifier register */ + uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + uint32_t TDLR; /*!< CAN mailbox data low register */ + uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +typedef struct +{ + uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +typedef struct +{ + uint32_t CNT; +} TIM_TypeDef; + +void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void toyota_init(int16_t param); +void set_controls_allowed(int c); +void reset_angle_control(void); +int get_controls_allowed(void); +void init_tests_toyota(void); +void set_timer(int t); +void set_toyota_torque_meas(int min, int max); +void set_cadillac_torque_driver(int min, int max); +void set_gm_torque_driver(int min, int max); +void set_hyundai_torque_driver(int min, int max); +void set_toyota_rt_torque_last(int t); +void set_toyota_desired_torque_last(int t); +int get_toyota_torque_meas_min(void); +int get_toyota_torque_meas_max(void); + +void init_tests_honda(void); +int get_ego_speed(void); +void honda_init(int16_t param); +void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +int get_brake_prev(void); +int get_gas_prev(void); +void set_honda_alt_brake_msg(bool); +void set_bosch_hardware(bool); + +void init_tests_cadillac(void); +void cadillac_init(int16_t param); +void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void set_cadillac_desired_torque_last(int t); +void set_cadillac_rt_torque_last(int t); + +void init_tests_gm(void); +void gm_init(int16_t param); +void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void set_gm_desired_torque_last(int t); +void set_gm_rt_torque_last(int t); + +void init_tests_hyundai(void); +void nooutput_init(int16_t param); +void hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void set_hyundai_desired_torque_last(int t); +void set_hyundai_rt_torque_last(int t); + +void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int toyota_ipas_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); + +void init_tests_chrysler(void); +void chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void chrysler_init(int16_t param); +void set_chrysler_desired_torque_last(int t); + +""") + +libpandasafety = ffi.dlopen(libpandasafety_fn) diff --git a/panda/tests/safety/requirements.txt b/panda/tests/safety/requirements.txt new file mode 100644 index 00000000000000..8bbfb1d7df38a2 --- /dev/null +++ b/panda/tests/safety/requirements.txt @@ -0,0 +1,2 @@ +cffi==1.11.4 +numpy==1.14.1 diff --git a/panda/tests/safety/test.c b/panda/tests/safety/test.c new file mode 100644 index 00000000000000..af0db3c92c1132 --- /dev/null +++ b/panda/tests/safety/test.c @@ -0,0 +1,203 @@ +#include +#include + +typedef struct +{ + uint32_t TIR; /*!< CAN TX mailbox identifier register */ + uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + uint32_t TDLR; /*!< CAN mailbox data low register */ + uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +typedef struct +{ + uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +typedef struct +{ + uint32_t CNT; +} TIM_TypeDef; + +struct sample_t toyota_torque_meas; +struct sample_t cadillac_torque_driver; +struct sample_t gm_torque_driver; +struct sample_t hyundai_torque_driver; + +TIM_TypeDef timer; +TIM_TypeDef *TIM2 = &timer; + +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + + +#define PANDA +#define static +#include "safety.h" + +void set_controls_allowed(int c){ + controls_allowed = c; +} + +void reset_angle_control(void){ + angle_control = 0; +} + +int get_controls_allowed(void){ + return controls_allowed; +} + +void set_timer(int t){ + timer.CNT = t; +} + +void set_toyota_torque_meas(int min, int max){ + toyota_torque_meas.min = min; + toyota_torque_meas.max = max; +} + +void set_cadillac_torque_driver(int min, int max){ + cadillac_torque_driver.min = min; + cadillac_torque_driver.max = max; +} + +void set_gm_torque_driver(int min, int max){ + gm_torque_driver.min = min; + gm_torque_driver.max = max; +} + +void set_hyundai_torque_driver(int min, int max){ + hyundai_torque_driver.min = min; + hyundai_torque_driver.max = max; +} + +int get_toyota_torque_meas_min(void){ + return toyota_torque_meas.min; +} + +int get_toyota_torque_meas_max(void){ + return toyota_torque_meas.max; +} + +void set_toyota_rt_torque_last(int t){ + toyota_rt_torque_last = t; +} + +void set_cadillac_rt_torque_last(int t){ + cadillac_rt_torque_last = t; +} + +void set_gm_rt_torque_last(int t){ + gm_rt_torque_last = t; +} + +void set_hyundai_rt_torque_last(int t){ + hyundai_rt_torque_last = t; +} + +void set_toyota_desired_torque_last(int t){ + toyota_desired_torque_last = t; +} + +void set_cadillac_desired_torque_last(int t){ + for (int i = 0; i < 4; i++) cadillac_desired_torque_last[i] = t; +} + +void set_gm_desired_torque_last(int t){ + gm_desired_torque_last = t; +} + +void set_hyundai_desired_torque_last(int t){ + hyundai_desired_torque_last = t; +} + +void set_chrysler_desired_torque_last(int t){ + chrysler_desired_torque_last = t; +} + +int get_ego_speed(void){ + return ego_speed; +} + +int get_brake_prev(void){ + return brake_prev; +} + +int get_gas_prev(void){ + return gas_prev; +} + +void set_honda_alt_brake_msg(bool c){ + honda_alt_brake_msg = c; +} + +void set_bosch_hardware(bool c){ + bosch_hardware = c; +} + +void init_tests_toyota(void){ + toyota_torque_meas.min = 0; + toyota_torque_meas.max = 0; + toyota_desired_torque_last = 0; + toyota_rt_torque_last = 0; + toyota_ts_last = 0; + set_timer(0); +} + +void init_tests_cadillac(void){ + cadillac_torque_driver.min = 0; + cadillac_torque_driver.max = 0; + for (int i = 0; i < 4; i++) cadillac_desired_torque_last[i] = 0; + cadillac_rt_torque_last = 0; + cadillac_ts_last = 0; + set_timer(0); +} + +void init_tests_gm(void){ + gm_torque_driver.min = 0; + gm_torque_driver.max = 0; + gm_desired_torque_last = 0; + gm_rt_torque_last = 0; + gm_ts_last = 0; + set_timer(0); +} + +void init_tests_hyundai(void){ + hyundai_torque_driver.min = 0; + hyundai_torque_driver.max = 0; + hyundai_desired_torque_last = 0; + hyundai_rt_torque_last = 0; + hyundai_ts_last = 0; + set_timer(0); +} + +void init_tests_honda(void){ + ego_speed = 0; + gas_interceptor_detected = 0; + brake_prev = 0; + gas_prev = 0; +} + +void init_tests_chrysler(void){ + chrysler_desired_torque_last = 0; + set_timer(0); +} + +void set_gmlan_digital_output(int to_set){ +} + +void reset_gmlan_switch_timeout(void){ +} + +void gmlan_switch_init(int timeout_enable){ +} diff --git a/panda/tests/safety/test.sh b/panda/tests/safety/test.sh new file mode 100755 index 00000000000000..83d8f5b31fa420 --- /dev/null +++ b/panda/tests/safety/test.sh @@ -0,0 +1,2 @@ +#!/usr/bin/env sh +python -m unittest discover . diff --git a/panda/tests/safety/test_cadillac.py b/panda/tests/safety/test_cadillac.py new file mode 100644 index 00000000000000..53c943e966d6fc --- /dev/null +++ b/panda/tests/safety/test_cadillac.py @@ -0,0 +1,182 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 2 +MAX_RATE_DOWN = 5 +MAX_TORQUE = 150 + +MAX_RT_DELTA = 75 +RT_INTERVAL = 250000 + +DRIVER_TORQUE_ALLOWANCE = 50; +DRIVER_TORQUE_FACTOR = 4; + +IPAS_OVERRIDE_THRESHOLD = 200 + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestCadillacSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.cadillac_init(0) + cls.safety.init_tests_cadillac() + + def _set_prev_torque(self, t): + self.safety.set_cadillac_desired_torque_last(t) + self.safety.set_cadillac_rt_torque_last(t) + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x164 << 21 + + t = twos_comp(torque, 11) + to_send[0].RDLR = ((t >> 8) & 0x7) | ((t & 0xFF) << 8) + return to_send + + def _torque_driver_msg_array(self, torque): + for i in range(3): + self.safety.cadillac_ipas_rx_hook(self._torque_driver_msg(torque)) + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x151 << 21 + + t = twos_comp(torque, 14) + to_send[0].RDLR = ((t >> 8) & 0x3F) | ((t & 0xFF) << 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(0) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x370 << 21 + to_push[0].RDLR = 0x800000 + to_push[0].RDTR = 0 + + self.safety.cadillac_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x370 << 21 + to_push[0].RDLR = 0 + to_push[0].RDTR = 0 + + self.safety.set_controls_allowed(1) + self.safety.cadillac_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_torque_absolute_limits(self): + for controls_allowed in [True, False]: + for torque in np.arange(-MAX_TORQUE - 1000, MAX_TORQUE + 1000, MAX_RATE_UP): + self.safety.set_controls_allowed(controls_allowed) + self.safety.set_cadillac_rt_torque_last(torque) + self.safety.set_cadillac_torque_driver(0, 0) + self.safety.set_cadillac_desired_torque_last(torque - MAX_RATE_UP) + + if controls_allowed: + send = (-MAX_TORQUE <= torque <= MAX_TORQUE) + else: + send = torque == 0 + + self.assertEqual(send, self.safety.cadillac_tx_hook(self._torque_msg(torque))) + + def test_non_realtime_limit_up(self): + self.safety.set_cadillac_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(MAX_RATE_UP))) + self._set_prev_torque(0) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(-MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + self.safety.set_controls_allowed(True) + self._set_prev_torque(0) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(-MAX_RATE_UP - 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_cadillac_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + def test_exceed_torque_sensor(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1): + t *= -sign + self.safety.set_cadillac_torque_driver(t, t) + self._set_prev_torque(MAX_TORQUE * sign) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(MAX_TORQUE * sign))) + + self.safety.set_cadillac_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(-MAX_TORQUE))) + + # spot check some individual cases + for sign in [-1, 1]: + driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign + torque_desired = (MAX_TORQUE - 10 * DRIVER_TORQUE_FACTOR) * sign + delta = 1 * sign + self._set_prev_torque(torque_desired) + self.safety.set_cadillac_torque_driver(-driver_torque, -driver_torque) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(torque_desired))) + self._set_prev_torque(torque_desired + delta) + self.safety.set_cadillac_torque_driver(-driver_torque, -driver_torque) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(torque_desired + delta))) + + self._set_prev_torque(MAX_TORQUE * sign) + self.safety.set_cadillac_torque_driver(-MAX_TORQUE * sign, -MAX_TORQUE * sign) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg((MAX_TORQUE - MAX_RATE_DOWN) * sign))) + self._set_prev_torque(MAX_TORQUE * sign) + self.safety.set_cadillac_torque_driver(-MAX_TORQUE * sign, -MAX_TORQUE * sign) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(0))) + self._set_prev_torque(MAX_TORQUE * sign) + self.safety.set_cadillac_torque_driver(-MAX_TORQUE * sign, -MAX_TORQUE * sign) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg((MAX_TORQUE - MAX_RATE_DOWN + 1) * sign))) + + + def test_realtime_limits(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_cadillac() + self._set_prev_torque(0) + self.safety.set_cadillac_torque_driver(0, 0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1)))) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_chrysler.py b/panda/tests/safety/test_chrysler.py new file mode 100755 index 00000000000000..9b8b17720f96e9 --- /dev/null +++ b/panda/tests/safety/test_chrysler.py @@ -0,0 +1,88 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + + +class TestChryslerSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.chrysler_init(0) + cls.safety.init_tests_chrysler() + + def _acc_msg(self, active): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x1f4 << 21 + to_send[0].RDLR = 0xfe3fff1f if active else 0xfe0fff1f + return to_send + + + def _brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x140 << 21 + to_send[0].RDLR = 0x485 if brake else 0x480 + return to_send + + def _steer_msg(self, angle): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x292 << 21 + c_angle = (1024 + angle) + to_send[0].RDLR = 0x10 | ((c_angle & 0xf00) >> 8) | ((c_angle & 0xff) << 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_acc_enables_controls(self): + self.safety.set_controls_allowed(0) + self.safety.chrysler_rx_hook(self._acc_msg(0)) + self.assertFalse(self.safety.get_controls_allowed()) + self.safety.chrysler_rx_hook(self._acc_msg(1)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.chrysler_rx_hook(self._acc_msg(0)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_disengage_on_brake(self): + self.safety.set_controls_allowed(1) + self.safety.chrysler_rx_hook(self._brake_msg(0)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.chrysler_rx_hook(self._brake_msg(1)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_steer_calculation(self): + self.assertEqual(0x14, self._steer_msg(0)[0].RDLR) # straight, no steering + + def test_steer_tx(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(0))) + self.safety.set_chrysler_desired_torque_last(227) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(230))) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(231))) + self.safety.set_chrysler_desired_torque_last(-227) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(-231))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(-230))) + # verify max change + self.safety.set_chrysler_desired_torque_last(0) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(230))) + + self.safety.set_controls_allowed(0) + self.safety.set_chrysler_desired_torque_last(0) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(3))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(0))) + # verify when controls not allowed we can still go back towards 0 + self.safety.set_chrysler_desired_torque_last(10) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(10))) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(11))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(7))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(4))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(0))) + self.safety.set_chrysler_desired_torque_last(-10) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(-10))) + self.assertFalse(self.safety.chrysler_tx_hook(self._steer_msg(-11))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(-7))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(-4))) + self.assertTrue(self.safety.chrysler_tx_hook(self._steer_msg(0))) + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_gm.py b/panda/tests/safety/test_gm.py new file mode 100644 index 00000000000000..299de5a7e9ff51 --- /dev/null +++ b/panda/tests/safety/test_gm.py @@ -0,0 +1,266 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 7 +MAX_RATE_DOWN = 17 +MAX_STEER = 300 +MAX_BRAKE = 350 +MAX_GAS = 3072 +MAX_REGEN = 1404 + +MAX_RT_DELTA = 128 +RT_INTERVAL = 250000 + +DRIVER_TORQUE_ALLOWANCE = 50; +DRIVER_TORQUE_FACTOR = 4; + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestGmSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.gm_init(0) + cls.safety.init_tests_gm() + + def _speed_msg(self, speed): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 842 << 21 + to_send[0].RDLR = speed + return to_send + + def _button_msg(self, buttons): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 481 << 21 + to_send[0].RDHR = buttons << 12 + return to_send + + def _brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 241 << 21 + to_send[0].RDLR = 0xa00 if brake else 0x900 + return to_send + + def _gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 417 << 21 + to_send[0].RDHR = (1 << 16) if gas else 0 + return to_send + + def _send_brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 789 << 21 + brake = (-brake) & 0xfff + to_send[0].RDLR = (brake >> 8) | ((brake &0xff) << 8) + return to_send + + def _send_gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 715 << 21 + to_send[0].RDLR = ((gas & 0x1f) << 27) | ((gas & 0xfe0) << 11) + return to_send + + def _set_prev_torque(self, t): + self.safety.set_gm_desired_torque_last(t) + self.safety.set_gm_rt_torque_last(t) + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 388 << 21 + + t = twos_comp(torque, 11) + to_send[0].RDHR = (((t >> 8) & 0x7) << 16) | ((t & 0xFF) << 24) + return to_send + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 384 << 21 + + t = twos_comp(torque, 11) + to_send[0].RDLR = ((t >> 8) & 0x7) | ((t & 0xFF) << 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_resume_button(self): + RESUME_BTN = 2 + self.safety.set_controls_allowed(0) + self.safety.gm_rx_hook(self._button_msg(RESUME_BTN)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_set_button(self): + SET_BTN = 3 + self.safety.set_controls_allowed(0) + self.safety.gm_rx_hook(self._button_msg(SET_BTN)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_cancel_button(self): + CANCEL_BTN = 6 + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._button_msg(CANCEL_BTN)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_disengage_on_brake(self): + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._brake_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_allow_brake_at_zero_speed(self): + # Brake was already pressed + self.safety.gm_rx_hook(self._brake_msg(True)) + self.safety.set_controls_allowed(1) + + self.safety.gm_rx_hook(self._brake_msg(True)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._brake_msg(False)) + + def test_not_allow_brake_when_moving(self): + # Brake was already pressed + self.safety.gm_rx_hook(self._brake_msg(True)) + self.safety.gm_rx_hook(self._speed_msg(100)) + self.safety.set_controls_allowed(1) + + self.safety.gm_rx_hook(self._brake_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._brake_msg(False)) + + def test_disengage_on_gas(self): + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._gas_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._gas_msg(False)) + + def test_allow_engage_with_gas_pressed(self): + self.safety.gm_rx_hook(self._gas_msg(True)) + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._gas_msg(True)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._gas_msg(False)) + + def test_brake_safety_check(self): + for enabled in [0, 1]: + for b in range(0, 500): + self.safety.set_controls_allowed(enabled) + if abs(b) > MAX_BRAKE or (not enabled and b != 0): + self.assertFalse(self.safety.gm_tx_hook(self._send_brake_msg(b))) + else: + self.assertTrue(self.safety.gm_tx_hook(self._send_brake_msg(b))) + + def test_gas_safety_check(self): + for enabled in [0, 1]: + for g in range(0, 2**12-1): + self.safety.set_controls_allowed(enabled) + if abs(g) > MAX_GAS or (not enabled and g != MAX_REGEN): + self.assertFalse(self.safety.gm_tx_hook(self._send_gas_msg(g))) + else: + self.assertTrue(self.safety.gm_tx_hook(self._send_gas_msg(g))) + + def test_steer_safety_check(self): + for enabled in [0, 1]: + for t in range(-0x200, 0x200): + self.safety.set_controls_allowed(enabled) + self._set_prev_torque(t) + if abs(t) > MAX_STEER or (not enabled and abs(t) > 0): + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(t))) + else: + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(t))) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(0) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_non_realtime_limit_up(self): + self.safety.set_gm_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(MAX_RATE_UP))) + self._set_prev_torque(0) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(-MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + self.safety.set_controls_allowed(True) + self._set_prev_torque(0) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(-MAX_RATE_UP - 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_gm_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + def test_against_torque_driver(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1): + t *= -sign + self.safety.set_gm_torque_driver(t, t) + self._set_prev_torque(MAX_STEER * sign) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(MAX_STEER * sign))) + + self.safety.set_gm_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(-MAX_STEER))) + + # spot check some individual cases + for sign in [-1, 1]: + driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign + torque_desired = (MAX_STEER - 10 * DRIVER_TORQUE_FACTOR) * sign + delta = 1 * sign + self._set_prev_torque(torque_desired) + self.safety.set_gm_torque_driver(-driver_torque, -driver_torque) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(torque_desired))) + self._set_prev_torque(torque_desired + delta) + self.safety.set_gm_torque_driver(-driver_torque, -driver_torque) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(torque_desired + delta))) + + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_gm_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN) * sign))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_gm_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(0))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_gm_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN + 1) * sign))) + + + def test_realtime_limits(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_gm() + self._set_prev_torque(0) + self.safety.set_gm_torque_driver(0, 0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1)))) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_honda.py b/panda/tests/safety/test_honda.py new file mode 100755 index 00000000000000..48b678eaaec43e --- /dev/null +++ b/panda/tests/safety/test_honda.py @@ -0,0 +1,185 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + + +class TestHondaSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.honda_init(0) + cls.safety.init_tests_honda() + + def _speed_msg(self, speed): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x158 << 21 + to_send[0].RDLR = speed + + return to_send + + def _button_msg(self, buttons, msg): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = msg << 21 + to_send[0].RDLR = buttons << 5 + + return to_send + + def _brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x17C << 21 + to_send[0].RDHR = 0x200000 if brake else 0 + + return to_send + + def _alt_brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x1BE << 21 + to_send[0].RDLR = 0x10 if brake else 0 + + return to_send + + def _gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x17C << 21 + to_send[0].RDLR = 1 if gas else 0 + + return to_send + + def _send_brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x1FA << 21 + to_send[0].RDLR = brake + + return to_send + + def _send_gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x200 << 21 + to_send[0].RDLR = gas + + return to_send + + def _send_steer_msg(self, steer): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0xE4 << 21 + to_send[0].RDLR = steer + + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_resume_button(self): + RESUME_BTN = 4 + self.safety.set_controls_allowed(0) + self.safety.honda_rx_hook(self._button_msg(RESUME_BTN, 0x1A6)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_set_button(self): + SET_BTN = 3 + self.safety.set_controls_allowed(0) + self.safety.honda_rx_hook(self._button_msg(SET_BTN, 0x1A6)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_cancel_button(self): + CANCEL_BTN = 2 + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._button_msg(CANCEL_BTN, 0x1A6)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_sample_speed(self): + self.assertEqual(0, self.safety.get_ego_speed()) + self.safety.honda_rx_hook(self._speed_msg(100)) + self.assertEqual(100, self.safety.get_ego_speed()) + + def test_prev_brake(self): + self.assertFalse(self.safety.get_brake_prev()) + self.safety.honda_rx_hook(self._brake_msg(True)) + self.assertTrue(self.safety.get_brake_prev()) + + def test_disengage_on_brake(self): + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._brake_msg(1)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_alt_disengage_on_brake(self): + self.safety.set_honda_alt_brake_msg(1) + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._alt_brake_msg(1)) + self.assertFalse(self.safety.get_controls_allowed()) + + self.safety.set_honda_alt_brake_msg(0) + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._alt_brake_msg(1)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_allow_brake_at_zero_speed(self): + # Brake was already pressed + self.safety.honda_rx_hook(self._brake_msg(True)) + self.safety.set_controls_allowed(1) + + self.safety.honda_rx_hook(self._brake_msg(True)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.honda_rx_hook(self._brake_msg(False)) # reset no brakes + + def test_not_allow_brake_when_moving(self): + # Brake was already pressed + self.safety.honda_rx_hook(self._brake_msg(True)) + self.safety.honda_rx_hook(self._speed_msg(100)) + self.safety.set_controls_allowed(1) + + self.safety.honda_rx_hook(self._brake_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_prev_gas(self): + self.assertFalse(self.safety.get_gas_prev()) + self.safety.honda_rx_hook(self._gas_msg(True)) + self.assertTrue(self.safety.get_gas_prev()) + + def test_disengage_on_gas(self): + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._gas_msg(1)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_allow_engage_with_gas_pressed(self): + self.safety.honda_rx_hook(self._gas_msg(1)) + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._gas_msg(1)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_brake_safety_check(self): + self.assertTrue(self.safety.honda_tx_hook(self._send_brake_msg(0x0000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_brake_msg(0x1000))) + + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.honda_tx_hook(self._send_brake_msg(0x1000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_brake_msg(0x00F0))) + + def test_gas_safety_check(self): + self.safety.set_controls_allowed(0) + self.assertTrue(self.safety.honda_tx_hook(self._send_gas_msg(0x0000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_gas_msg(0x1000))) + + def test_steer_safety_check(self): + self.safety.set_controls_allowed(0) + self.assertTrue(self.safety.honda_tx_hook(self._send_steer_msg(0x0000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_steer_msg(0x1000))) + + def test_spam_cancel_safety_check(self): + RESUME_BTN = 4 + SET_BTN = 3 + CANCEL_BTN = 2 + BUTTON_MSG = 0x296 + self.safety.set_bosch_hardware(1) + self.safety.set_controls_allowed(0) + self.assertTrue(self.safety.honda_tx_hook(self._button_msg(CANCEL_BTN, BUTTON_MSG))) + self.assertFalse(self.safety.honda_tx_hook(self._button_msg(RESUME_BTN, BUTTON_MSG))) + self.assertFalse(self.safety.honda_tx_hook(self._button_msg(SET_BTN, BUTTON_MSG))) + # do not block resume if we are engaged already + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.honda_tx_hook(self._button_msg(RESUME_BTN, BUTTON_MSG))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_hyundai.py b/panda/tests/safety/test_hyundai.py new file mode 100644 index 00000000000000..0a6ce0f91f3d03 --- /dev/null +++ b/panda/tests/safety/test_hyundai.py @@ -0,0 +1,186 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 3 +MAX_RATE_DOWN = 7 +MAX_STEER = 250 + +MAX_RT_DELTA = 112 +RT_INTERVAL = 250000 + +DRIVER_TORQUE_ALLOWANCE = 50; +DRIVER_TORQUE_FACTOR = 2; + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestHyundaiSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.nooutput_init(0) + cls.safety.init_tests_hyundai() + + def _button_msg(self, buttons): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 1265 << 21 + to_send[0].RDLR = buttons + return to_send + + def _set_prev_torque(self, t): + self.safety.set_hyundai_desired_torque_last(t) + self.safety.set_hyundai_rt_torque_last(t) + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 897 << 21 + to_send[0].RDLR = (torque + 2048) << 11 + return to_send + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 832 << 21 + to_send[0].RDLR = (torque + 1024) << 16 + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_steer_safety_check(self): + for enabled in [0, 1]: + for t in range(-0x200, 0x200): + self.safety.set_controls_allowed(enabled) + self._set_prev_torque(t) + if abs(t) > MAX_STEER or (not enabled and abs(t) > 0): + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(t))) + else: + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(t))) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(0) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 1057 << 21 + to_push[0].RDLR = 1 << 13 + + self.safety.hyundai_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 1057 << 21 + to_push[0].RDLR = 0 + + self.safety.set_controls_allowed(1) + self.safety.hyundai_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_non_realtime_limit_up(self): + self.safety.set_hyundai_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(MAX_RATE_UP))) + self._set_prev_torque(0) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(-MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + self.safety.set_controls_allowed(True) + self._set_prev_torque(0) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(-MAX_RATE_UP - 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_hyundai_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + def test_against_torque_driver(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1): + t *= -sign + self.safety.set_hyundai_torque_driver(t, t) + self._set_prev_torque(MAX_STEER * sign) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(MAX_STEER * sign))) + + self.safety.set_hyundai_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(-MAX_STEER))) + + # spot check some individual cases + for sign in [-1, 1]: + driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign + torque_desired = (MAX_STEER - 10 * DRIVER_TORQUE_FACTOR) * sign + delta = 1 * sign + self._set_prev_torque(torque_desired) + self.safety.set_hyundai_torque_driver(-driver_torque, -driver_torque) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(torque_desired))) + self._set_prev_torque(torque_desired + delta) + self.safety.set_hyundai_torque_driver(-driver_torque, -driver_torque) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(torque_desired + delta))) + + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_hyundai_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN) * sign))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_hyundai_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(0))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_hyundai_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN + 1) * sign))) + + + def test_realtime_limits(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_hyundai() + self._set_prev_torque(0) + self.safety.set_hyundai_torque_driver(0, 0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1)))) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + + #def test_spam_cancel_safety_check(self): + # RESUME_BTN = 1 + # SET_BTN = 2 + # CANCEL_BTN = 4 + # BUTTON_MSG = 1265 + # self.safety.set_controls_allowed(0) + # self.assertTrue(self.safety.hyundai_tx_hook(self._button_msg(CANCEL_BTN))) + # self.assertFalse(self.safety.hyundai_tx_hook(self._button_msg(RESUME_BTN))) + # self.assertFalse(self.safety.hyundai_tx_hook(self._button_msg(SET_BTN))) + # # do not block resume if we are engaged already + # self.safety.set_controls_allowed(1) + # self.assertTrue(self.safety.hyundai_tx_hook(self._button_msg(RESUME_BTN))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_toyota.py b/panda/tests/safety/test_toyota.py new file mode 100644 index 00000000000000..40bc4bcf5d8f97 --- /dev/null +++ b/panda/tests/safety/test_toyota.py @@ -0,0 +1,414 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 10 +MAX_RATE_DOWN = 25 +MAX_TORQUE = 1500 + +MAX_ACCEL = 1500 +MIN_ACCEL = -3000 + +MAX_RT_DELTA = 375 +RT_INTERVAL = 250000 + +MAX_TORQUE_ERROR = 350 + +IPAS_OVERRIDE_THRESHOLD = 200 + +ANGLE_DELTA_BP = [0., 5., 15.] +ANGLE_DELTA_V = [5., .8, .15] # windup limit +ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestToyotaSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.toyota_init(100) + cls.safety.init_tests_toyota() + + def _set_prev_torque(self, t): + self.safety.set_toyota_desired_torque_last(t) + self.safety.set_toyota_rt_torque_last(t) + self.safety.set_toyota_torque_meas(t, t) + + def _torque_meas_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x260 << 21 + + t = twos_comp(torque, 16) + to_send[0].RDHR = t | ((t & 0xFF) << 16) + return to_send + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x260 << 21 + + t = twos_comp(torque, 16) + to_send[0].RDLR = t | ((t & 0xFF) << 16) + return to_send + + def _torque_driver_msg_array(self, torque): + for i in range(6): + self.safety.toyota_ipas_rx_hook(self._torque_driver_msg(torque)) + + def _angle_meas_msg(self, angle): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x25 << 21 + + t = twos_comp(angle, 12) + to_send[0].RDLR = ((t & 0xF00) >> 8) | ((t & 0xFF) << 8) + return to_send + + def _angle_meas_msg_array(self, angle): + for i in range(6): + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(angle)) + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x2E4 << 21 + + t = twos_comp(torque, 16) + to_send[0].RDLR = t | ((t & 0xFF) << 16) + return to_send + + def _ipas_state_msg(self, state): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x262 << 21 + + to_send[0].RDLR = state & 0xF + return to_send + + def _ipas_control_msg(self, angle, state): + # note: we command 2/3 of the angle due to CAN conversion + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x266 << 21 + + t = twos_comp(angle, 12) + to_send[0].RDLR = ((t & 0xF00) >> 8) | ((t & 0xFF) << 8) + to_send[0].RDLR |= ((state & 0xf) << 4) + + return to_send + + def _speed_msg(self, speed): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0xb4 << 21 + speed = int(speed * 100 * 3.6) + + to_send[0].RDHR = ((speed & 0xFF) << 16) | (speed & 0xFF00) + return to_send + + def _accel_msg(self, accel): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x343 << 21 + + a = twos_comp(accel, 16) + to_send[0].RDLR = (a & 0xFF) << 8 | (a >> 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x1D2 << 21 + to_push[0].RDLR = 0x20 + + self.safety.toyota_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x1D2 << 21 + to_push[0].RDLR = 0 + + self.safety.set_controls_allowed(1) + self.safety.toyota_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_accel_actuation_limits(self): + for accel in np.arange(MIN_ACCEL - 1000, MAX_ACCEL + 1000, 100): + for controls_allowed in [True, False]: + self.safety.set_controls_allowed(controls_allowed) + + if controls_allowed: + send = MIN_ACCEL <= accel <= MAX_ACCEL + else: + send = accel == 0 + self.assertEqual(send, self.safety.toyota_tx_hook(self._accel_msg(accel))) + + def test_torque_absolute_limits(self): + for controls_allowed in [True, False]: + for torque in np.arange(-MAX_TORQUE - 1000, MAX_TORQUE + 1000, MAX_RATE_UP): + self.safety.set_controls_allowed(controls_allowed) + self.safety.set_toyota_rt_torque_last(torque) + self.safety.set_toyota_torque_meas(torque, torque) + self.safety.set_toyota_desired_torque_last(torque - MAX_RATE_UP) + + if controls_allowed: + send = (-MAX_TORQUE <= torque <= MAX_TORQUE) + else: + send = torque == 0 + + self.assertEqual(send, self.safety.toyota_tx_hook(self._torque_msg(torque))) + + def test_non_realtime_limit_up(self): + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_controls_allowed(True) + + self.safety.set_toyota_rt_torque_last(1000) + self.safety.set_toyota_torque_meas(500, 500) + self.safety.set_toyota_desired_torque_last(1000) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN))) + + self.safety.set_toyota_rt_torque_last(1000) + self.safety.set_toyota_torque_meas(500, 500) + self.safety.set_toyota_desired_torque_last(1000) + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN + 1))) + + def test_exceed_torque_sensor(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self._set_prev_torque(0) + for t in np.arange(0, MAX_TORQUE_ERROR + 10, 10): + t *= sign + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) + + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(sign * (MAX_TORQUE_ERROR + 10)))) + + def test_realtime_limit_up(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_toyota() + self._set_prev_torque(0) + for t in np.arange(0, 380, 10): + t *= sign + self.safety.set_toyota_torque_meas(t, t) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(sign * 380))) + + self._set_prev_torque(0) + for t in np.arange(0, 370, 10): + t *= sign + self.safety.set_toyota_torque_meas(t, t) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(sign * 370))) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(sign * 380))) + + def test_torque_measurements(self): + self.safety.toyota_rx_hook(self._torque_meas_msg(50)) + self.safety.toyota_rx_hook(self._torque_meas_msg(-50)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + + self.assertEqual(-51, self.safety.get_toyota_torque_meas_min()) + self.assertEqual(51, self.safety.get_toyota_torque_meas_max()) + + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_max()) + self.assertEqual(-51, self.safety.get_toyota_torque_meas_min()) + + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_max()) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_min()) + + def test_ipas_override(self): + + ## angle control is not active + self.safety.set_controls_allowed(1) + + # 3 consecutive msgs where driver exceeds threshold but angle_control isn't active + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(IPAS_OVERRIDE_THRESHOLD + 1) + self.assertTrue(self.safety.get_controls_allowed()) + + self._torque_driver_msg_array(-IPAS_OVERRIDE_THRESHOLD - 1) + self.assertTrue(self.safety.get_controls_allowed()) + + # ipas state is override + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(5)) + self.assertTrue(self.safety.get_controls_allowed()) + + ## now angle control is active + self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 0)) + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(0)) + + # 3 consecutive msgs where driver does exceed threshold + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(IPAS_OVERRIDE_THRESHOLD + 1) + self.assertFalse(self.safety.get_controls_allowed()) + + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(-IPAS_OVERRIDE_THRESHOLD - 1) + self.assertFalse(self.safety.get_controls_allowed()) + + # ipas state is override and torque isn't overriding any more + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(0) + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(5)) + self.assertFalse(self.safety.get_controls_allowed()) + + # 3 consecutive msgs where driver does not exceed threshold and + # ipas state is not override + self.safety.set_controls_allowed(1) + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(0)) + self.assertTrue(self.safety.get_controls_allowed()) + + self._torque_driver_msg_array(IPAS_OVERRIDE_THRESHOLD) + self.assertTrue(self.safety.get_controls_allowed()) + + self._torque_driver_msg_array(-IPAS_OVERRIDE_THRESHOLD) + self.assertTrue(self.safety.get_controls_allowed()) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_cmd_when_disabled(self): + + self.safety.set_controls_allowed(0) + + # test angle cmd too far from actual + angle_refs = [-10, 10] + deltas = range(-2, 3) + expected_results = [False, True, True, True, False] + + for a in angle_refs: + self._angle_meas_msg_array(a) + for i, d in enumerate(deltas): + self.assertEqual(expected_results[i], self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + d, 1))) + + # test ipas state cmd enabled + self._angle_meas_msg_array(0) + self.assertEqual(0, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 3))) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_cmd_when_enabled(self): + + # ipas angle cmd should pass through when controls are enabled + + self.safety.set_controls_allowed(1) + self._angle_meas_msg_array(0) + self.safety.toyota_ipas_rx_hook(self._speed_msg(0.1)) + + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 1))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(4, 1))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 3))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(-4, 3))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(-8, 3))) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + + def test_angle_cmd_rate_when_disabled(self): + + # as long as the command is close to the measured, no rate limit is enforced when + # controls are disabled + self.safety.set_controls_allowed(0) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(0)) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 1))) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(100)) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(100, 1))) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(-100)) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(-100, 1))) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_cmd_rate_when_enabled(self): + + # when controls are allowed, angle cmd rate limit is enforced + # test 1: no limitations if we stay within limits + speeds = [0., 1., 5., 10., 15., 100.] + angles = [-300, -100, -10, 0, 10, 100, 300] + for a in angles: + for s in speeds: + + # first test against false positives + self._angle_meas_msg_array(a) + self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1)) + self.safety.set_controls_allowed(1) + self.safety.toyota_ipas_rx_hook(self._speed_msg(s)) + max_delta_up = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_V) * 2 / 3. + 1.) + max_delta_down = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_VU) * 2 / 3. + 1.) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + sign(a) * max_delta_up, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a - sign(a) * max_delta_down, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + + # now inject too high rates + self.assertEqual(False, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + sign(a) * + (max_delta_up + 1), 1))) + self.assertFalse(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(1) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + sign(a) * max_delta_up, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(False, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a - sign(a) * + (max_delta_down + 1), 1))) + self.assertFalse(self.safety.get_controls_allowed()) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_measured_rate(self): + + speeds = [0., 1., 5., 10., 15., 100.] + angles = [-300, -100, -10, 0, 10, 100, 300] + angles = [10] + for a in angles: + for s in speeds: + self._angle_meas_msg_array(a) + self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1)) + self.safety.set_controls_allowed(1) + self.safety.toyota_ipas_rx_hook(self._speed_msg(s)) + max_delta_up = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_V) * 2 / 3. + 1.) + max_delta_down = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_VU) * 2 / 3. + 1.) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(a)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(a + 150)) + self.assertFalse(self.safety.get_controls_allowed()) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/standalone_test.py b/panda/tests/standalone_test.py index 76df0235bc7272..ca6ea49f1056de 100755 --- a/panda/tests/standalone_test.py +++ b/panda/tests/standalone_test.py @@ -21,7 +21,7 @@ t2 = time.time() print("100 requests took %.2f ms" % ((t2-t1)*1000)) - p.set_controls_allowed(True) + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) a = 0 while True: diff --git a/panda/tests/tucan_loopback.py b/panda/tests/tucan_loopback.py new file mode 100755 index 00000000000000..a3f3e6e2d7cbad --- /dev/null +++ b/panda/tests/tucan_loopback.py @@ -0,0 +1,125 @@ +#!/usr/bin/env python +from __future__ import print_function +import os +import sys +import time +import random +import argparse + +from hexdump import hexdump +from itertools import permutations + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +def get_test_string(): + return b"test"+os.urandom(10) + +def run_test(sleep_duration): + pandas = Panda.list() + print(pandas) + + if len(pandas) == 0: + print("NO PANDAS") + assert False + + if len(pandas) == 1: + # if we only have one on USB, assume the other is on wifi + pandas.append("WIFI") + run_test_w_pandas(pandas, sleep_duration) + +def run_test_w_pandas(pandas, sleep_duration): + h = list(map(lambda x: Panda(x), pandas)) + print("H", h) + + for hh in h: + hh.set_controls_allowed(True) + + # test both directions + for ho in permutations(range(len(h)), r=2): + print("***************** TESTING", ho) + + panda0, panda1 = h[ho[0]], h[ho[1]] + + if(panda0._serial == "WIFI"): + print(" *** Can not send can data over wifi panda. Skipping! ***") + continue + + # **** test health packet **** + print("health", ho[0], h[ho[0]].health()) + + # **** test K/L line loopback **** + for bus in [2,3]: + # flush the output + h[ho[1]].kline_drain(bus=bus) + + # send the characters + st = get_test_string() + st = b"\xaa"+chr(len(st)+3).encode()+st + h[ho[0]].kline_send(st, bus=bus, checksum=False) + + # check for receive + ret = h[ho[1]].kline_drain(bus=bus) + + print("ST Data:") + hexdump(st) + print("RET Data:") + hexdump(ret) + assert st == ret + print("K/L pass", bus, ho, "\n") + time.sleep(sleep_duration) + + # **** test can line loopback **** +# for bus, gmlan in [(0, None), (1, False), (2, False), (1, True), (2, True)]: +for bus, gmlan in [(0, None), (1, None)]: + print("\ntest can", bus) + # flush + cans_echo = panda0.can_recv() + cans_loop = panda1.can_recv() + + if gmlan is not None: + panda0.set_gmlan(gmlan, bus) + panda1.set_gmlan(gmlan, bus) + + # send the characters + # pick addresses high enough to not conflict with honda code + at = random.randint(1024, 2000) + st = get_test_string()[0:8] + panda0.can_send(at, st, bus) + time.sleep(0.1) + + # check for receive + cans_echo = panda0.can_recv() + cans_loop = panda1.can_recv() + + print("Bus", bus, "echo", cans_echo, "loop", cans_loop) + + assert len(cans_echo) == 1 + assert len(cans_loop) == 1 + + assert cans_echo[0][0] == at + assert cans_loop[0][0] == at + + assert cans_echo[0][2] == st + assert cans_loop[0][2] == st + + assert cans_echo[0][3] == 0x80 | bus + if cans_loop[0][3] != bus: + print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3])) + assert cans_loop[0][3] == bus + + print("CAN pass", bus, ho) + time.sleep(sleep_duration) + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("-n", type=int, help="Number of test iterations to run") + parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) + args = parser.parse_args() + + if args.n is None: + while True: + run_test(sleep_duration=args.sleep) + else: + for i in range(args.n): + run_test(sleep_duration=args.sleep) diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnp b/phonelibs/capnp-cpp/aarch64/bin/capnp new file mode 100755 index 00000000000000..e60fe7fe3c1ba0 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/bin/capnp differ diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnpc b/phonelibs/capnp-cpp/aarch64/bin/capnpc new file mode 120000 index 00000000000000..5668473f09dafe --- /dev/null +++ b/phonelibs/capnp-cpp/aarch64/bin/capnpc @@ -0,0 +1 @@ +capnp \ No newline at end of file diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnpc-c++ b/phonelibs/capnp-cpp/aarch64/bin/capnpc-c++ new file mode 100755 index 00000000000000..d3090911446257 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/bin/capnpc-c++ differ diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnpc-capnp b/phonelibs/capnp-cpp/aarch64/bin/capnpc-capnp new file mode 100755 index 00000000000000..b1c7a9a9b818b6 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/bin/capnpc-capnp differ diff --git a/phonelibs/capnp-cpp/aarch64/lib/libcapnp.a b/phonelibs/capnp-cpp/aarch64/lib/libcapnp.a new file mode 100644 index 00000000000000..a997023caa4e1b Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/lib/libcapnp.a differ diff --git a/phonelibs/capnp-cpp/aarch64/lib/libcapnpc.a b/phonelibs/capnp-cpp/aarch64/lib/libcapnpc.a new file mode 100644 index 00000000000000..2ede39fb910a33 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/lib/libcapnpc.a differ diff --git a/phonelibs/capnp-cpp/aarch64/lib/libkj.a b/phonelibs/capnp-cpp/aarch64/lib/libkj.a new file mode 100644 index 00000000000000..58cf096637f027 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/lib/libkj.a differ diff --git a/phonelibs/capnp-cpp/include/capnp/any.h b/phonelibs/capnp-cpp/include/capnp/any.h new file mode 100644 index 00000000000000..6df9dc8dc2dcea --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/any.h @@ -0,0 +1,1073 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_ANY_H_ +#define CAPNP_ANY_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" +#include "pointer-helpers.h" +#include "orphan.h" +#include "list.h" + +namespace capnp { + +class StructSchema; +class ListSchema; +class InterfaceSchema; +class Orphanage; +class ClientHook; +class PipelineHook; +struct PipelineOp; +struct AnyPointer; + +struct AnyList { + AnyList() = delete; + + class Reader; + class Builder; +}; + +struct AnyStruct { + AnyStruct() = delete; + + class Reader; + class Builder; + class Pipeline; +}; + +template<> +struct List { + List() = delete; + + class Reader; + class Builder; +}; + +namespace _ { // private +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +} // namespace _ (private) + +// ======================================================================================= +// AnyPointer! + +enum class Equality { + NOT_EQUAL, + EQUAL, + UNKNOWN_CONTAINS_CAPS +}; + +kj::StringPtr KJ_STRINGIFY(Equality res); + +struct AnyPointer { + // Reader/Builder for the `AnyPointer` field type, i.e. a pointer that can point to an arbitrary + // object. + + AnyPointer() = delete; + + class Reader { + public: + typedef AnyPointer Reads; + + Reader() = default; + inline Reader(_::PointerReader reader): reader(reader) {} + + inline MessageSize targetSize() const; + // Get the total size of the target object and all its children. + + inline PointerType getPointerType() const; + + inline bool isNull() const { return getPointerType() == PointerType::NULL_; } + inline bool isStruct() const { return getPointerType() == PointerType::STRUCT; } + inline bool isList() const { return getPointerType() == PointerType::LIST; } + inline bool isCapability() const { return getPointerType() == PointerType::CAPABILITY; } + + Equality equals(AnyPointer::Reader right); + bool operator==(AnyPointer::Reader right); + inline bool operator!=(AnyPointer::Reader right) { + return !(*this == right); + } + + template + inline ReaderFor getAs() const; + // Valid for T = any generated struct type, interface type, List, Text, or Data. + + template + inline ReaderFor getAs(StructSchema schema) const; + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline ReaderFor getAs(ListSchema schema) const; + // Only valid for T = DynamicList. Requires `#include `. + + template + inline ReaderFor getAs(InterfaceSchema schema) const; + // Only valid for T = DynamicCapability. Requires `#include `. + +#if !CAPNP_LITE + kj::Own getPipelinedCap(kj::ArrayPtr ops) const; + // Used by RPC system to implement pipelining. Applications generally shouldn't use this + // directly. +#endif // !CAPNP_LITE + + private: + _::PointerReader reader; + friend struct AnyPointer; + friend class Orphanage; + friend class CapReaderContext; + friend struct _::PointerHelpers; + }; + + class Builder { + public: + typedef AnyPointer Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)) {} + inline Builder(_::PointerBuilder builder): builder(builder) {} + + inline MessageSize targetSize() const; + // Get the total size of the target object and all its children. + + inline PointerType getPointerType(); + + inline bool isNull() { return getPointerType() == PointerType::NULL_; } + inline bool isStruct() { return getPointerType() == PointerType::STRUCT; } + inline bool isList() { return getPointerType() == PointerType::LIST; } + inline bool isCapability() { return getPointerType() == PointerType::CAPABILITY; } + + inline Equality equals(AnyPointer::Reader right) { + return asReader().equals(right); + } + inline bool operator==(AnyPointer::Reader right) { + return asReader() == right; + } + inline bool operator!=(AnyPointer::Reader right) { + return !(*this == right); + } + + inline void clear(); + // Set to null. + + template + inline BuilderFor getAs(); + // Valid for T = any generated struct type, List, Text, or Data. + + template + inline BuilderFor getAs(StructSchema schema); + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline BuilderFor getAs(ListSchema schema); + // Only valid for T = DynamicList. Requires `#include `. + + template + inline BuilderFor getAs(InterfaceSchema schema); + // Only valid for T = DynamicCapability. Requires `#include `. + + template + inline BuilderFor initAs(); + // Valid for T = any generated struct type. + + template + inline BuilderFor initAs(uint elementCount); + // Valid for T = List, Text, or Data. + + template + inline BuilderFor initAs(StructSchema schema); + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline BuilderFor initAs(ListSchema schema, uint elementCount); + // Only valid for T = DynamicList. Requires `#include `. + + inline AnyList::Builder initAsAnyList(ElementSize elementSize, uint elementCount); + // Note: Does not accept INLINE_COMPOSITE for elementSize. + + inline List::Builder initAsListOfAnyStruct( + uint16_t dataWordCount, uint16_t pointerCount, uint elementCount); + + inline AnyStruct::Builder initAsAnyStruct(uint16_t dataWordCount, uint16_t pointerCount); + + template + inline void setAs(ReaderFor value); + // Valid for ReaderType = T::Reader for T = any generated struct type, List, Text, Data, + // DynamicStruct, or DynamicList (the dynamic types require `#include `). + + template + inline void setAs(std::initializer_list>> list); + // Valid for T = List. + + template + inline void setCanonicalAs(ReaderFor value); + + inline void set(Reader value) { builder.copyFrom(value.reader); } + // Set to a copy of another AnyPointer. + + inline void setCanonical(Reader value) { builder.copyFrom(value.reader, true); } + + template + inline void adopt(Orphan&& orphan); + // Valid for T = any generated struct type, List, Text, Data, DynamicList, DynamicStruct, + // or DynamicValue (the dynamic types require `#include `). + + template + inline Orphan disownAs(); + // Valid for T = any generated struct type, List, Text, Data. + + template + inline Orphan disownAs(StructSchema schema); + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline Orphan disownAs(ListSchema schema); + // Only valid for T = DynamicList. Requires `#include `. + + template + inline Orphan disownAs(InterfaceSchema schema); + // Only valid for T = DynamicCapability. Requires `#include `. + + inline Orphan disown(); + // Disown without a type. + + inline Reader asReader() const { return Reader(builder.asReader()); } + inline operator Reader() const { return Reader(builder.asReader()); } + + private: + _::PointerBuilder builder; + friend class Orphanage; + friend class CapBuilderContext; + friend struct _::PointerHelpers; + }; + +#if !CAPNP_LITE + class Pipeline { + public: + typedef AnyPointer Pipelines; + + inline Pipeline(decltype(nullptr)) {} + inline explicit Pipeline(kj::Own&& hook): hook(kj::mv(hook)) {} + + Pipeline noop(); + // Just make a copy. + + Pipeline getPointerField(uint16_t pointerIndex); + // Deprecated. In the future, we should use .asAnyStruct.getPointerField. + + inline AnyStruct::Pipeline asAnyStruct(); + + kj::Own asCap(); + // Expect that the result is a capability and construct a pipelined version of it now. + + inline kj::Own releasePipelineHook() { return kj::mv(hook); } + // For use by RPC implementations. + + template ) == Kind::INTERFACE>> + inline operator T() { return T(asCap()); } + + private: + kj::Own hook; + kj::Array ops; + + inline Pipeline(kj::Own&& hook, kj::Array&& ops) + : hook(kj::mv(hook)), ops(kj::mv(ops)) {} + + friend class LocalClient; + friend class PipelineHook; + friend class AnyStruct::Pipeline; + }; +#endif // !CAPNP_LITE +}; + +template <> +class Orphan { + // An orphaned object of unknown type. + +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + inline Orphan(_::OrphanBuilder&& builder) + : builder(kj::mv(builder)) {} + + Orphan& operator=(Orphan&&) = default; + + template + inline Orphan(Orphan&& other): builder(kj::mv(other.builder)) {} + template + inline Orphan& operator=(Orphan&& other) { builder = kj::mv(other.builder); return *this; } + // Cast from typed orphan. + + // It's not possible to get an AnyPointer::{Reader,Builder} directly since there is no + // underlying pointer (the pointer would normally live in the parent, but this object is + // orphaned). It is possible, however, to request typed readers/builders. + + template + inline BuilderFor getAs(); + template + inline BuilderFor getAs(StructSchema schema); + template + inline BuilderFor getAs(ListSchema schema); + template + inline typename T::Client getAs(InterfaceSchema schema); + template + inline ReaderFor getAsReader() const; + template + inline ReaderFor getAsReader(StructSchema schema) const; + template + inline ReaderFor getAsReader(ListSchema schema) const; + template + inline typename T::Client getAsReader(InterfaceSchema schema) const; + + template + inline Orphan releaseAs(); + template + inline Orphan releaseAs(StructSchema schema); + template + inline Orphan releaseAs(ListSchema schema); + template + inline Orphan releaseAs(InterfaceSchema schema); + // Down-cast the orphan to a specific type. + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + _::OrphanBuilder builder; + + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend class Orphan; + friend class AnyPointer::Builder; +}; + +template struct AnyTypeFor_; +template <> struct AnyTypeFor_ { typedef AnyStruct Type; }; +template <> struct AnyTypeFor_ { typedef AnyList Type; }; + +template +using AnyTypeFor = typename AnyTypeFor_::Type; + +template +inline ReaderFor>> toAny(T&& value) { + return ReaderFor>>( + _::PointerHelpers>::getInternalReader(value)); +} +template +inline BuilderFor>> toAny(T&& value) { + return BuilderFor>>( + _::PointerHelpers>::getInternalBuilder(kj::mv(value))); +} + +template <> +struct List { + // Note: This cannot be used for a list of structs, since such lists are not encoded as pointer + // lists! Use List. + + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(ElementSize::POINTER) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline AnyPointer::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return AnyPointer::Reader(reader.getPointerElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)): builder(ElementSize::POINTER) {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline AnyPointer::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return AnyPointer::Builder(builder.getPointerElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; +}; + +class AnyStruct::Reader { +public: + typedef AnyStruct Reads; + + Reader() = default; + inline Reader(_::StructReader reader): _reader(reader) {} + + template ) == Kind::STRUCT>> + inline Reader(T&& value) + : _reader(_::PointerHelpers>::getInternalReader(kj::fwd(value))) {} + + kj::ArrayPtr getDataSection() { + return _reader.getDataSectionAsBlob(); + } + List::Reader getPointerSection() { + return List::Reader(_reader.getPointerSectionAsList()); + } + + kj::Array canonicalize() { + return _reader.canonicalize(); + } + + Equality equals(AnyStruct::Reader right); + bool operator==(AnyStruct::Reader right); + inline bool operator!=(AnyStruct::Reader right) { + return !(*this == right); + } + + template + ReaderFor as() const { + // T must be a struct type. + return typename T::Reader(_reader); + } +private: + _::StructReader _reader; + + template + friend struct _::PointerHelpers; + friend class Orphanage; +}; + +class AnyStruct::Builder { +public: + typedef AnyStruct Builds; + + inline Builder(decltype(nullptr)) {} + inline Builder(_::StructBuilder builder): _builder(builder) {} + +#if !_MSC_VER // TODO(msvc): MSVC ICEs on this. Try restoring when compiler improves. + template ) == Kind::STRUCT>> + inline Builder(T&& value) + : _builder(_::PointerHelpers>::getInternalBuilder(kj::fwd(value))) {} +#endif + + inline kj::ArrayPtr getDataSection() { + return _builder.getDataSectionAsBlob(); + } + List::Builder getPointerSection() { + return List::Builder(_builder.getPointerSectionAsList()); + } + + inline Equality equals(AnyStruct::Reader right) { + return asReader().equals(right); + } + inline bool operator==(AnyStruct::Reader right) { + return asReader() == right; + } + inline bool operator!=(AnyStruct::Reader right) { + return !(*this == right); + } + + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return Reader(_builder.asReader()); } + + template + BuilderFor as() { + // T must be a struct type. + return typename T::Builder(_builder); + } +private: + _::StructBuilder _builder; + friend class Orphanage; + friend class CapBuilderContext; +}; + +#if !CAPNP_LITE +class AnyStruct::Pipeline { +public: + inline Pipeline(decltype(nullptr)): typeless(nullptr) {} + inline explicit Pipeline(AnyPointer::Pipeline&& typeless) + : typeless(kj::mv(typeless)) {} + + inline AnyPointer::Pipeline getPointerField(uint16_t pointerIndex) { + // Return a new Promise representing a sub-object of the result. `pointerIndex` is the index + // of the sub-object within the pointer section of the result (the result must be a struct). + // + // TODO(perf): On GCC 4.8 / Clang 3.3, use rvalue qualifiers to avoid the need for copies. + // Also make `ops` into a Vector to optimize this. + return typeless.getPointerField(pointerIndex); + } + +private: + AnyPointer::Pipeline typeless; +}; +#endif // !CAPNP_LITE + +class List::Reader { +public: + typedef List Reads; + + inline Reader(): reader(ElementSize::INLINE_COMPOSITE) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline AnyStruct::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return AnyStruct::Reader(reader.getStructElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; +}; + +class List::Builder { +public: + typedef List Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)): builder(ElementSize::INLINE_COMPOSITE) {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline AnyStruct::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return AnyStruct::Builder(builder.getStructElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + +private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; +}; + +class AnyList::Reader { +public: + typedef AnyList Reads; + + inline Reader(): _reader(ElementSize::VOID) {} + inline Reader(_::ListReader reader): _reader(reader) {} + +#if !_MSC_VER // TODO(msvc): MSVC ICEs on this. Try restoring when compiler improves. + template ) == Kind::LIST>> + inline Reader(T&& value) + : _reader(_::PointerHelpers>::getInternalReader(kj::fwd(value))) {} +#endif + + inline ElementSize getElementSize() { return _reader.getElementSize(); } + inline uint size() { return unbound(_reader.size() / ELEMENTS); } + + inline kj::ArrayPtr getRawBytes() { return _reader.asRawBytes(); } + + Equality equals(AnyList::Reader right); + bool operator==(AnyList::Reader right); + inline bool operator!=(AnyList::Reader right) { + return !(*this == right); + } + + template ReaderFor as() { + // T must be List. + return ReaderFor(_reader); + } +private: + _::ListReader _reader; + + template + friend struct _::PointerHelpers; + friend class Orphanage; +}; + +class AnyList::Builder { +public: + typedef AnyList Builds; + + inline Builder(decltype(nullptr)): _builder(ElementSize::VOID) {} + inline Builder(_::ListBuilder builder): _builder(builder) {} + +#if !_MSC_VER // TODO(msvc): MSVC ICEs on this. Try restoring when compiler improves. + template ) == Kind::LIST>> + inline Builder(T&& value) + : _builder(_::PointerHelpers>::getInternalBuilder(kj::fwd(value))) {} +#endif + + inline ElementSize getElementSize() { return _builder.getElementSize(); } + inline uint size() { return unbound(_builder.size() / ELEMENTS); } + + Equality equals(AnyList::Reader right); + inline bool operator==(AnyList::Reader right) { + return asReader() == right; + } + inline bool operator!=(AnyList::Reader right) { + return !(*this == right); + } + + template BuilderFor as() { + // T must be List. + return BuilderFor(_builder); + } + + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return Reader(_builder.asReader()); } + +private: + _::ListBuilder _builder; + + friend class Orphanage; +}; + +// ======================================================================================= +// Pipeline helpers +// +// These relate to capabilities, but we don't declare them in capability.h because generated code +// for structs needs to know about these, even in files that contain no interfaces. + +#if !CAPNP_LITE + +struct PipelineOp { + // Corresponds to rpc.capnp's PromisedAnswer.Op. + + enum Type { + NOOP, // for convenience + + GET_POINTER_FIELD + + // There may be other types in the future... + }; + + Type type; + union { + uint16_t pointerIndex; // for GET_POINTER_FIELD + }; +}; + +class PipelineHook { + // Represents a currently-running call, and implements pipelined requests on its result. + +public: + virtual kj::Own addRef() = 0; + // Increment this object's reference count. + + virtual kj::Own getPipelinedCap(kj::ArrayPtr ops) = 0; + // Extract a promised Capability from the results. + + virtual kj::Own getPipelinedCap(kj::Array&& ops); + // Version of getPipelinedCap() passing the array by move. May avoid a copy in some cases. + // Default implementation just calls the other version. + + template > + static inline kj::Own from(Pipeline&& pipeline); + +private: + template struct FromImpl; +}; + +#endif // !CAPNP_LITE + +// ======================================================================================= +// Inline implementation details + +inline MessageSize AnyPointer::Reader::targetSize() const { + return reader.targetSize().asPublic(); +} + +inline PointerType AnyPointer::Reader::getPointerType() const { + return reader.getPointerType(); +} + +template +inline ReaderFor AnyPointer::Reader::getAs() const { + return _::PointerHelpers::get(reader); +} + +inline MessageSize AnyPointer::Builder::targetSize() const { + return asReader().targetSize(); +} + +inline PointerType AnyPointer::Builder::getPointerType() { + return builder.getPointerType(); +} + +inline void AnyPointer::Builder::clear() { + return builder.clear(); +} + +template +inline BuilderFor AnyPointer::Builder::getAs() { + return _::PointerHelpers::get(builder); +} + +template +inline BuilderFor AnyPointer::Builder::initAs() { + return _::PointerHelpers::init(builder); +} + +template +inline BuilderFor AnyPointer::Builder::initAs(uint elementCount) { + return _::PointerHelpers::init(builder, elementCount); +} + +inline AnyList::Builder AnyPointer::Builder::initAsAnyList( + ElementSize elementSize, uint elementCount) { + return AnyList::Builder(builder.initList(elementSize, bounded(elementCount) * ELEMENTS)); +} + +inline List::Builder AnyPointer::Builder::initAsListOfAnyStruct( + uint16_t dataWordCount, uint16_t pointerCount, uint elementCount) { + return List::Builder(builder.initStructList(bounded(elementCount) * ELEMENTS, + _::StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); +} + +inline AnyStruct::Builder AnyPointer::Builder::initAsAnyStruct( + uint16_t dataWordCount, uint16_t pointerCount) { + return AnyStruct::Builder(builder.initStruct( + _::StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); +} + +template +inline void AnyPointer::Builder::setAs(ReaderFor value) { + return _::PointerHelpers::set(builder, value); +} + +template +inline void AnyPointer::Builder::setCanonicalAs(ReaderFor value) { + return _::PointerHelpers::setCanonical(builder, value); +} + +template +inline void AnyPointer::Builder::setAs( + std::initializer_list>> list) { + return _::PointerHelpers::set(builder, list); +} + +template +inline void AnyPointer::Builder::adopt(Orphan&& orphan) { + _::PointerHelpers::adopt(builder, kj::mv(orphan)); +} + +template +inline Orphan AnyPointer::Builder::disownAs() { + return _::PointerHelpers::disown(builder); +} + +inline Orphan AnyPointer::Builder::disown() { + return Orphan(builder.disown()); +} + +template <> struct ReaderFor_ { typedef AnyPointer::Reader Type; }; +template <> struct BuilderFor_ { typedef AnyPointer::Builder Type; }; +template <> struct ReaderFor_ { typedef AnyStruct::Reader Type; }; +template <> struct BuilderFor_ { typedef AnyStruct::Builder Type; }; + +template <> +struct Orphanage::GetInnerReader { + static inline _::PointerReader apply(const AnyPointer::Reader& t) { + return t.reader; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::PointerBuilder apply(AnyPointer::Builder& t) { + return t.builder; + } +}; + +template <> +struct Orphanage::GetInnerReader { + static inline _::StructReader apply(const AnyStruct::Reader& t) { + return t._reader; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::StructBuilder apply(AnyStruct::Builder& t) { + return t._builder; + } +}; + +template <> +struct Orphanage::GetInnerReader { + static inline _::ListReader apply(const AnyList::Reader& t) { + return t._reader; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::ListBuilder apply(AnyList::Builder& t) { + return t._builder; + } +}; + +template +inline BuilderFor Orphan::getAs() { + return _::OrphanGetImpl::apply(builder); +} +template +inline ReaderFor Orphan::getAsReader() const { + return _::OrphanGetImpl::applyReader(builder); +} +template +inline Orphan Orphan::releaseAs() { + return Orphan(kj::mv(builder)); +} + +// Using AnyPointer as the template type should work... + +template <> +inline typename AnyPointer::Reader AnyPointer::Reader::getAs() const { + return *this; +} +template <> +inline typename AnyPointer::Builder AnyPointer::Builder::getAs() { + return *this; +} +template <> +inline typename AnyPointer::Builder AnyPointer::Builder::initAs() { + clear(); + return *this; +} +template <> +inline void AnyPointer::Builder::setAs(AnyPointer::Reader value) { + return builder.copyFrom(value.reader); +} +template <> +inline void AnyPointer::Builder::adopt(Orphan&& orphan) { + builder.adopt(kj::mv(orphan.builder)); +} +template <> +inline Orphan AnyPointer::Builder::disownAs() { + return Orphan(builder.disown()); +} +template <> +inline Orphan Orphan::releaseAs() { + return kj::mv(*this); +} + +namespace _ { // private + +// Specialize PointerHelpers for AnyPointer. + +template <> +struct PointerHelpers { + static inline AnyPointer::Reader get(PointerReader reader, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return AnyPointer::Reader(reader); + } + static inline AnyPointer::Builder get(PointerBuilder builder, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return AnyPointer::Builder(builder); + } + static inline void set(PointerBuilder builder, AnyPointer::Reader value) { + AnyPointer::Builder(builder).set(value); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } + static inline _::PointerReader getInternalReader(const AnyPointer::Reader& reader) { + return reader.reader; + } + static inline _::PointerBuilder getInternalBuilder(AnyPointer::Builder&& builder) { + return builder.builder; + } +}; + +template <> +struct PointerHelpers { + static inline AnyStruct::Reader get( + PointerReader reader, const word* defaultValue = nullptr) { + return AnyStruct::Reader(reader.getStruct(defaultValue)); + } + static inline AnyStruct::Builder get( + PointerBuilder builder, const word* defaultValue = nullptr) { + // TODO(someday): Allow specifying the size somehow? + return AnyStruct::Builder(builder.getStruct( + _::StructSize(ZERO * WORDS, ZERO * POINTERS), defaultValue)); + } + static inline void set(PointerBuilder builder, AnyStruct::Reader value) { + builder.setStruct(value._reader); + } + static inline AnyStruct::Builder init( + PointerBuilder builder, uint16_t dataWordCount, uint16_t pointerCount) { + return AnyStruct::Builder(builder.initStruct( + StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); + } + + static void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +template <> +struct PointerHelpers { + static inline AnyList::Reader get( + PointerReader reader, const word* defaultValue = nullptr) { + return AnyList::Reader(reader.getListAnySize(defaultValue)); + } + static inline AnyList::Builder get( + PointerBuilder builder, const word* defaultValue = nullptr) { + return AnyList::Builder(builder.getListAnySize(defaultValue)); + } + static inline void set(PointerBuilder builder, AnyList::Reader value) { + builder.setList(value._reader); + } + static inline AnyList::Builder init( + PointerBuilder builder, ElementSize elementSize, uint elementCount) { + return AnyList::Builder(builder.initList( + elementSize, bounded(elementCount) * ELEMENTS)); + } + static inline AnyList::Builder init( + PointerBuilder builder, uint16_t dataWordCount, uint16_t pointerCount, uint elementCount) { + return AnyList::Builder(builder.initStructList( + bounded(elementCount) * ELEMENTS, + StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); + } + + static void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +template <> +struct OrphanGetImpl { + static inline AnyStruct::Builder apply(_::OrphanBuilder& builder) { + return AnyStruct::Builder(builder.asStruct(_::StructSize(ZERO * WORDS, ZERO * POINTERS))); + } + static inline AnyStruct::Reader applyReader(const _::OrphanBuilder& builder) { + return AnyStruct::Reader(builder.asStructReader(_::StructSize(ZERO * WORDS, ZERO * POINTERS))); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, _::StructSize(ZERO * WORDS, ZERO * POINTERS)); + } +}; + +template <> +struct OrphanGetImpl { + static inline AnyList::Builder apply(_::OrphanBuilder& builder) { + return AnyList::Builder(builder.asListAnySize()); + } + static inline AnyList::Reader applyReader(const _::OrphanBuilder& builder) { + return AnyList::Reader(builder.asListReaderAnySize()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +} // namespace _ (private) + +#if !CAPNP_LITE + +template +struct PipelineHook::FromImpl { + static inline kj::Own apply(typename T::Pipeline&& pipeline) { + return from(kj::mv(pipeline._typeless)); + } +}; + +template <> +struct PipelineHook::FromImpl { + static inline kj::Own apply(AnyPointer::Pipeline&& pipeline) { + return kj::mv(pipeline.hook); + } +}; + +template +inline kj::Own PipelineHook::from(Pipeline&& pipeline) { + return FromImpl::apply(kj::fwd(pipeline)); +} + +#endif // !CAPNP_LITE + +} // namespace capnp + +#endif // CAPNP_ANY_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/blob.h b/phonelibs/capnp-cpp/include/capnp/blob.h new file mode 100644 index 00000000000000..d11f101a5ad378 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/blob.h @@ -0,0 +1,220 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_BLOB_H_ +#define CAPNP_BLOB_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include +#include "common.h" +#include + +namespace capnp { + +struct Data { + Data() = delete; + class Reader; + class Builder; + class Pipeline {}; +}; + +struct Text { + Text() = delete; + class Reader; + class Builder; + class Pipeline {}; +}; + +class Data::Reader: public kj::ArrayPtr { + // Points to a blob of bytes. The usual Reader rules apply -- Data::Reader behaves like a simple + // pointer which does not own its target, can be passed by value, etc. + +public: + typedef Data Reads; + + Reader() = default; + inline Reader(decltype(nullptr)): ArrayPtr(nullptr) {} + inline Reader(const byte* value, size_t size): ArrayPtr(value, size) {} + inline Reader(const kj::Array& value): ArrayPtr(value) {} + inline Reader(const ArrayPtr& value): ArrayPtr(value) {} + inline Reader(const kj::Array& value): ArrayPtr(value) {} + inline Reader(const ArrayPtr& value): ArrayPtr(value) {} +}; + +class Text::Reader: public kj::StringPtr { + // Like Data::Reader, but points at NUL-terminated UTF-8 text. The NUL terminator is not counted + // in the size but must be present immediately after the last byte. + // + // Text::Reader's interface contract is that its data MUST be NUL-terminated. The producer of + // the Text::Reader must guarantee this, so that the consumer need not check. The data SHOULD + // also be valid UTF-8, but this is NOT guaranteed -- the consumer must verify if it cares. + +public: + typedef Text Reads; + + Reader() = default; + inline Reader(decltype(nullptr)): StringPtr(nullptr) {} + inline Reader(const char* value): StringPtr(value) {} + inline Reader(const char* value, size_t size): StringPtr(value, size) {} + inline Reader(const kj::String& value): StringPtr(value) {} + inline Reader(const StringPtr& value): StringPtr(value) {} + +#if KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP + template ().c_str())> + inline Reader(const T& t): StringPtr(t) {} + // Allow implicit conversion from any class that has a c_str() method (namely, std::string). + // We use a template trick to detect std::string in order to avoid including the header for + // those who don't want it. +#endif +}; + +class Data::Builder: public kj::ArrayPtr { + // Like Data::Reader except the pointers aren't const. + +public: + typedef Data Builds; + + Builder() = default; + inline Builder(decltype(nullptr)): ArrayPtr(nullptr) {} + inline Builder(byte* value, size_t size): ArrayPtr(value, size) {} + inline Builder(kj::Array& value): ArrayPtr(value) {} + inline Builder(ArrayPtr value): ArrayPtr(value) {} + + inline Data::Reader asReader() const { return Data::Reader(*this); } + inline operator Reader() const { return asReader(); } +}; + +class Text::Builder: public kj::DisallowConstCopy { + // Basically identical to kj::StringPtr, except that the contents are non-const. + +public: + inline Builder(): content(nulstr, 1) {} + inline Builder(decltype(nullptr)): content(nulstr, 1) {} + inline Builder(char* value): content(value, strlen(value) + 1) {} + inline Builder(char* value, size_t size): content(value, size + 1) { + KJ_IREQUIRE(value[size] == '\0', "StringPtr must be NUL-terminated."); + } + + inline Reader asReader() const { return Reader(content.begin(), content.size() - 1); } + inline operator Reader() const { return asReader(); } + + inline operator kj::ArrayPtr(); + inline kj::ArrayPtr asArray(); + inline operator kj::ArrayPtr() const; + inline kj::ArrayPtr asArray() const; + inline kj::ArrayPtr asBytes() { return asArray().asBytes(); } + inline kj::ArrayPtr asBytes() const { return asArray().asBytes(); } + // Result does not include NUL terminator. + + inline operator kj::StringPtr() const; + inline kj::StringPtr asString() const; + + inline const char* cStr() const { return content.begin(); } + // Returns NUL-terminated string. + + inline size_t size() const { return content.size() - 1; } + // Result does not include NUL terminator. + + inline char operator[](size_t index) const { return content[index]; } + inline char& operator[](size_t index) { return content[index]; } + + inline char* begin() { return content.begin(); } + inline char* end() { return content.end() - 1; } + inline const char* begin() const { return content.begin(); } + inline const char* end() const { return content.end() - 1; } + + inline bool operator==(decltype(nullptr)) const { return content.size() <= 1; } + inline bool operator!=(decltype(nullptr)) const { return content.size() > 1; } + + inline bool operator==(Builder other) const { return asString() == other.asString(); } + inline bool operator!=(Builder other) const { return asString() != other.asString(); } + inline bool operator< (Builder other) const { return asString() < other.asString(); } + inline bool operator> (Builder other) const { return asString() > other.asString(); } + inline bool operator<=(Builder other) const { return asString() <= other.asString(); } + inline bool operator>=(Builder other) const { return asString() >= other.asString(); } + + inline kj::StringPtr slice(size_t start) const; + inline kj::ArrayPtr slice(size_t start, size_t end) const; + inline Builder slice(size_t start); + inline kj::ArrayPtr slice(size_t start, size_t end); + // A string slice is only NUL-terminated if it is a suffix, so slice() has a one-parameter + // version that assumes end = size(). + +private: + inline explicit Builder(kj::ArrayPtr content): content(content) {} + + kj::ArrayPtr content; + + static char nulstr[1]; +}; + +inline kj::StringPtr KJ_STRINGIFY(Text::Builder builder) { + return builder.asString(); +} + +inline bool operator==(const char* a, const Text::Builder& b) { return a == b.asString(); } +inline bool operator!=(const char* a, const Text::Builder& b) { return a != b.asString(); } + +inline Text::Builder::operator kj::StringPtr() const { + return kj::StringPtr(content.begin(), content.size() - 1); +} + +inline kj::StringPtr Text::Builder::asString() const { + return kj::StringPtr(content.begin(), content.size() - 1); +} + +inline Text::Builder::operator kj::ArrayPtr() { + return content.slice(0, content.size() - 1); +} + +inline kj::ArrayPtr Text::Builder::asArray() { + return content.slice(0, content.size() - 1); +} + +inline Text::Builder::operator kj::ArrayPtr() const { + return content.slice(0, content.size() - 1); +} + +inline kj::ArrayPtr Text::Builder::asArray() const { + return content.slice(0, content.size() - 1); +} + +inline kj::StringPtr Text::Builder::slice(size_t start) const { + return asReader().slice(start); +} +inline kj::ArrayPtr Text::Builder::slice(size_t start, size_t end) const { + return content.slice(start, end); +} + +inline Text::Builder Text::Builder::slice(size_t start) { + return Text::Builder(content.slice(start, content.size())); +} +inline kj::ArrayPtr Text::Builder::slice(size_t start, size_t end) { + return content.slice(start, end); +} + +} // namespace capnp + +#endif // CAPNP_BLOB_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/c++.capnp b/phonelibs/capnp-cpp/include/capnp/c++.capnp new file mode 100644 index 00000000000000..2bda54717920ab --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/c++.capnp @@ -0,0 +1,26 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xbdf87d7bb8304e81; +$namespace("capnp::annotations"); + +annotation namespace(file): Text; +annotation name(field, enumerant, struct, enum, interface, method, param, group, union): Text; diff --git a/phonelibs/capnp-cpp/include/capnp/c++.capnp.h b/phonelibs/capnp-cpp/include/capnp/c++.capnp.h new file mode 100644 index 00000000000000..6d9817fbded116 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/c++.capnp.h @@ -0,0 +1,33 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: c++.capnp + +#ifndef CAPNP_INCLUDED_bdf87d7bb8304e81_ +#define CAPNP_INCLUDED_bdf87d7bb8304e81_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(b9c6f99ebf805f2c); +CAPNP_DECLARE_SCHEMA(f264a779fef191ce); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace annotations { + +// ======================================================================================= + +// ======================================================================================= + +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_bdf87d7bb8304e81_ diff --git a/phonelibs/capnp-cpp/include/capnp/c.capnp b/phonelibs/capnp-cpp/include/capnp/c.capnp new file mode 100644 index 00000000000000..5de7e7363afcc0 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/c.capnp @@ -0,0 +1,37 @@ +# Copyright (c) 2016 NetDEF, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xc0183dd65ffef0f3; + +annotation nameinfix @0x85a8d86d736ba637 (file): Text; +# add an infix (middle insert) for output file names +# +# "make" generally has implicit rules for compiling "foo.c" => "foo". This +# is very annoying with capnp since the rule will be "foo" => "foo.c", leading +# to a loop. $nameinfix (recommended parameter: "-gen") inserts its parameter +# before the ".c", so the filename becomes "foo-gen.c" +# +# ("foo" is really "foo.capnp", so it's foo.capnp-gen.c) + +annotation fieldgetset @0xf72bc690355d66de (file): Void; +# generate getter & setter functions for accessing fields +# +# allows grabbing/putting values without de-/encoding the entire struct. diff --git a/phonelibs/capnp-cpp/include/capnp/capability.h b/phonelibs/capnp-cpp/include/capnp/capability.h new file mode 100644 index 00000000000000..56a5e6f6de2d38 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/capability.h @@ -0,0 +1,884 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_CAPABILITY_H_ +#define CAPNP_CAPABILITY_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#if CAPNP_LITE +#error "RPC APIs, including this header, are not available in lite mode." +#endif + +#include +#include +#include "raw-schema.h" +#include "any.h" +#include "pointer-helpers.h" + +namespace capnp { + +template +class Response; + +template +class RemotePromise: public kj::Promise>, public T::Pipeline { + // A Promise which supports pipelined calls. T is typically a struct type. T must declare + // an inner "mix-in" type "Pipeline" which implements pipelining; RemotePromise simply + // multiply-inherits that type along with Promise>. T::Pipeline must be movable, + // but does not need to be copyable (i.e. just like Promise). + // + // The promise is for an owned pointer so that the RPC system can allocate the MessageReader + // itself. + +public: + inline RemotePromise(kj::Promise>&& promise, typename T::Pipeline&& pipeline) + : kj::Promise>(kj::mv(promise)), + T::Pipeline(kj::mv(pipeline)) {} + inline RemotePromise(decltype(nullptr)) + : kj::Promise>(nullptr), + T::Pipeline(nullptr) {} + KJ_DISALLOW_COPY(RemotePromise); + RemotePromise(RemotePromise&& other) = default; + RemotePromise& operator=(RemotePromise&& other) = default; +}; + +class LocalClient; +namespace _ { // private +extern const RawSchema NULL_INTERFACE_SCHEMA; // defined in schema.c++ +class CapabilityServerSetBase; +} // namespace _ (private) + +struct Capability { + // A capability without type-safe methods. Typed capability clients wrap `Client` and typed + // capability servers subclass `Server` to dispatch to the regular, typed methods. + + class Client; + class Server; + + struct _capnpPrivate { + struct IsInterface; + static constexpr uint64_t typeId = 0x3; + static constexpr Kind kind = Kind::INTERFACE; + static constexpr _::RawSchema const* schema = &_::NULL_INTERFACE_SCHEMA; + + static const _::RawBrandedSchema* brand() { + return &_::NULL_INTERFACE_SCHEMA.defaultBrand; + } + }; +}; + +// ======================================================================================= +// Capability clients + +class RequestHook; +class ResponseHook; +class PipelineHook; +class ClientHook; + +template +class Request: public Params::Builder { + // A call that hasn't been sent yet. This class extends a Builder for the call's "Params" + // structure with a method send() that actually sends it. + // + // Given a Cap'n Proto method `foo(a :A, b :B): C`, the generated client interface will have + // a method `Request fooRequest()` (as well as a convenience method + // `RemotePromise foo(A::Reader a, B::Reader b)`). + +public: + inline Request(typename Params::Builder builder, kj::Own&& hook) + : Params::Builder(builder), hook(kj::mv(hook)) {} + inline Request(decltype(nullptr)): Params::Builder(nullptr) {} + + RemotePromise send() KJ_WARN_UNUSED_RESULT; + // Send the call and return a promise for the results. + +private: + kj::Own hook; + + friend class Capability::Client; + friend struct DynamicCapability; + template + friend class CallContext; + friend class RequestHook; +}; + +template +class Response: public Results::Reader { + // A completed call. This class extends a Reader for the call's answer structure. The Response + // is move-only -- once it goes out-of-scope, the underlying message will be freed. + +public: + inline Response(typename Results::Reader reader, kj::Own&& hook) + : Results::Reader(reader), hook(kj::mv(hook)) {} + +private: + kj::Own hook; + + template + friend class Request; + friend class ResponseHook; +}; + +class Capability::Client { + // Base type for capability clients. + +public: + typedef Capability Reads; + typedef Capability Calls; + + Client(decltype(nullptr)); + // If you need to declare a Client before you have anything to assign to it (perhaps because + // the assignment is going to occur in an if/else scope), you can start by initializing it to + // `nullptr`. The resulting client is not meant to be called and throws exceptions from all + // methods. + + template ()>> + Client(kj::Own&& server); + // Make a client capability that wraps the given server capability. The server's methods will + // only be executed in the given EventLoop, regardless of what thread calls the client's methods. + + template ()>> + Client(kj::Promise&& promise); + // Make a client from a promise for a future client. The resulting client queues calls until the + // promise resolves. + + Client(kj::Exception&& exception); + // Make a broken client that throws the given exception from all calls. + + Client(Client& other); + Client& operator=(Client& other); + // Copies by reference counting. Warning: This refcounting is not thread-safe. All copies of + // the client must remain in one thread. + + Client(Client&&) = default; + Client& operator=(Client&&) = default; + // Move constructor avoids reference counting. + + explicit Client(kj::Own&& hook); + // For use by the RPC implementation: Wrap a ClientHook. + + template + typename T::Client castAs(); + // Reinterpret the capability as implementing the given interface. Note that no error will occur + // here if the capability does not actually implement this interface, but later method calls will + // fail. It's up to the application to decide how indicate that additional interfaces are + // supported. + // + // TODO(perf): GCC 4.8 / Clang 3.3: rvalue-qualified version for better performance. + + template + typename T::Client castAs(InterfaceSchema schema); + // Dynamic version. `T` must be `DynamicCapability`, and you must `#include `. + + kj::Promise whenResolved(); + // If the capability is actually only a promise, the returned promise resolves once the + // capability itself has resolved to its final destination (or propagates the exception if + // the capability promise is rejected). This is mainly useful for error-checking in the case + // where no calls are being made. There is no reason to wait for this before making calls; if + // the capability does not resolve, the call results will propagate the error. + + Request typelessRequest( + uint64_t interfaceId, uint16_t methodId, + kj::Maybe sizeHint); + // Make a request without knowing the types of the params or results. You specify the type ID + // and method number manually. + + // TODO(someday): method(s) for Join + +protected: + Client() = default; + + template + Request newCall(uint64_t interfaceId, uint16_t methodId, + kj::Maybe sizeHint); + +private: + kj::Own hook; + + static kj::Own makeLocalClient(kj::Own&& server); + + template + friend struct _::PointerHelpers; + friend struct DynamicCapability; + friend class Orphanage; + friend struct DynamicStruct; + friend struct DynamicList; + template + friend struct List; + friend class _::CapabilityServerSetBase; + friend class ClientHook; +}; + +// ======================================================================================= +// Capability servers + +class CallContextHook; + +template +class CallContext: public kj::DisallowConstCopy { + // Wrapper around CallContextHook with a specific return type. + // + // Methods of this class may only be called from within the server's event loop, not from other + // threads. + // + // The CallContext becomes invalid as soon as the call reports completion. + +public: + explicit CallContext(CallContextHook& hook); + + typename Params::Reader getParams(); + // Get the params payload. + + void releaseParams(); + // Release the params payload. getParams() will throw an exception after this is called. + // Releasing the params may allow the RPC system to free up buffer space to handle other + // requests. Long-running asynchronous methods should try to call this as early as is + // convenient. + + typename Results::Builder getResults(kj::Maybe sizeHint = nullptr); + typename Results::Builder initResults(kj::Maybe sizeHint = nullptr); + void setResults(typename Results::Reader value); + void adoptResults(Orphan&& value); + Orphanage getResultsOrphanage(kj::Maybe sizeHint = nullptr); + // Manipulate the results payload. The "Return" message (part of the RPC protocol) will + // typically be allocated the first time one of these is called. Some RPC systems may + // allocate these messages in a limited space (such as a shared memory segment), therefore the + // application should delay calling these as long as is convenient to do so (but don't delay + // if doing so would require extra copies later). + // + // `sizeHint` indicates a guess at the message size. This will usually be used to decide how + // much space to allocate for the first message segment (don't worry: only space that is actually + // used will be sent on the wire). If omitted, the system decides. The message root pointer + // should not be included in the size. So, if you are simply going to copy some existing message + // directly into the results, just call `.totalSize()` and pass that in. + + template + kj::Promise tailCall(Request&& tailRequest); + // Resolve the call by making a tail call. `tailRequest` is a request that has been filled in + // but not yet sent. The context will send the call, then fill in the results with the result + // of the call. If tailCall() is used, {get,init,set,adopt}Results (above) *must not* be called. + // + // The RPC implementation may be able to optimize a tail call to another machine such that the + // results never actually pass through this machine. Even if no such optimization is possible, + // `tailCall()` may allow pipelined calls to be forwarded optimistically to the new call site. + // + // In general, this should be the last thing a method implementation calls, and the promise + // returned from `tailCall()` should then be returned by the method implementation. + + void allowCancellation(); + // Indicate that it is OK for the RPC system to discard its Promise for this call's result if + // the caller cancels the call, thereby transitively canceling any asynchronous operations the + // call implementation was performing. This is not done by default because it could represent a + // security risk: applications must be carefully written to ensure that they do not end up in + // a bad state if an operation is canceled at an arbitrary point. However, for long-running + // method calls that hold significant resources, prompt cancellation is often useful. + // + // Keep in mind that asynchronous cancellation cannot occur while the method is synchronously + // executing on a local thread. The method must perform an asynchronous operation or call + // `EventLoop::current().evalLater()` to yield control. + // + // Note: You might think that we should offer `onCancel()` and/or `isCanceled()` methods that + // provide notification when the caller cancels the request without forcefully killing off the + // promise chain. Unfortunately, this composes poorly with promise forking: the canceled + // path may be just one branch of a fork of the result promise. The other branches still want + // the call to continue. Promise forking is used within the Cap'n Proto implementation -- in + // particular each pipelined call forks the result promise. So, if a caller made a pipelined + // call and then dropped the original object, the call should not be canceled, but it would be + // excessively complicated for the framework to avoid notififying of cancellation as long as + // pipelined calls still exist. + +private: + CallContextHook* hook; + + friend class Capability::Server; + friend struct DynamicCapability; +}; + +class Capability::Server { + // Objects implementing a Cap'n Proto interface must subclass this. Typically, such objects + // will instead subclass a typed Server interface which will take care of implementing + // dispatchCall(). + +public: + typedef Capability Serves; + + virtual kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + CallContext context) = 0; + // Call the given method. `params` is the input struct, and should be released as soon as it + // is no longer needed. `context` may be used to allocate the output struct and deal with + // cancellation. + + // TODO(someday): Method which can optionally be overridden to implement Join when the object is + // a proxy. + +protected: + inline Capability::Client thisCap(); + // Get a capability pointing to this object, much like the `this` keyword. + // + // The effect of this method is undefined if: + // - No capability client has been created pointing to this object. (This is always the case in + // the server's constructor.) + // - The capability client pointing at this object has been destroyed. (This is always the case + // in the server's destructor.) + // - Multiple capability clients have been created around the same server (possible if the server + // is refcounted, which is not recommended since the client itself provides refcounting). + + template + CallContext internalGetTypedContext( + CallContext typeless); + kj::Promise internalUnimplemented(const char* actualInterfaceName, + uint64_t requestedTypeId); + kj::Promise internalUnimplemented(const char* interfaceName, + uint64_t typeId, uint16_t methodId); + kj::Promise internalUnimplemented(const char* interfaceName, const char* methodName, + uint64_t typeId, uint16_t methodId); + +private: + ClientHook* thisHook = nullptr; + friend class LocalClient; +}; + +// ======================================================================================= + +class ReaderCapabilityTable: private _::CapTableReader { + // Class which imbues Readers with the ability to read capabilities. + // + // In Cap'n Proto format, the encoding of a capability pointer is simply an integer index into + // an external table. Since these pointers fundamentally point outside the message, a + // MessageReader by default has no idea what they point at, and therefore reading capabilities + // from such a reader will throw exceptions. + // + // In order to be able to read capabilities, you must first attach a capability table, using + // this class. By "imbuing" a Reader, you get a new Reader which will interpret capability + // pointers by treating them as indexes into the ReaderCapabilityTable. + // + // Note that when using Cap'n Proto's RPC system, this is handled automatically. + +public: + explicit ReaderCapabilityTable(kj::Array>> table); + KJ_DISALLOW_COPY(ReaderCapabilityTable); + + template + T imbue(T reader); + // Return a reader equivalent to `reader` except that when reading capability-valued fields, + // the capabilities are looked up in this table. + +private: + kj::Array>> table; + + kj::Maybe> extractCap(uint index) override; +}; + +class BuilderCapabilityTable: private _::CapTableBuilder { + // Class which imbues Builders with the ability to read and write capabilities. + // + // This is much like ReaderCapabilityTable, except for builders. The table starts out empty, + // but capabilities can be added to it over time. + +public: + BuilderCapabilityTable(); + KJ_DISALLOW_COPY(BuilderCapabilityTable); + + inline kj::ArrayPtr>> getTable() { return table; } + + template + T imbue(T builder); + // Return a builder equivalent to `builder` except that when reading capability-valued fields, + // the capabilities are looked up in this table. + +private: + kj::Vector>> table; + + kj::Maybe> extractCap(uint index) override; + uint injectCap(kj::Own&& cap) override; + void dropCap(uint index) override; +}; + +// ======================================================================================= + +namespace _ { // private + +class CapabilityServerSetBase { +public: + Capability::Client addInternal(kj::Own&& server, void* ptr); + kj::Promise getLocalServerInternal(Capability::Client& client); +}; + +} // namespace _ (private) + +template +class CapabilityServerSet: private _::CapabilityServerSetBase { + // Allows a server to recognize its own capabilities when passed back to it, and obtain the + // underlying Server objects associated with them. + // + // All objects in the set must have the same interface type T. The objects may implement various + // interfaces derived from T (and in fact T can be `capnp::Capability` to accept all objects), + // but note that if you compile with RTTI disabled then you will not be able to down-cast through + // virtual inheritance, and all inheritance between server interfaces is virtual. So, with RTTI + // disabled, you will likely need to set T to be the most-derived Cap'n Proto interface type, + // and you server class will need to be directly derived from that, so that you can use + // static_cast (or kj::downcast) to cast to it after calling getLocalServer(). (If you compile + // with RTTI, then you can freely dynamic_cast and ignore this issue!) + +public: + CapabilityServerSet() = default; + KJ_DISALLOW_COPY(CapabilityServerSet); + + typename T::Client add(kj::Own&& server); + // Create a new capability Client for the given Server and also add this server to the set. + + kj::Promise> getLocalServer(typename T::Client& client); + // Given a Client pointing to a server previously passed to add(), return the corresponding + // Server. This returns a promise because if the input client is itself a promise, this must + // wait for it to resolve. Keep in mind that the server will be deleted when all clients are + // gone, so the caller should make sure to keep the client alive (hence why this method only + // accepts an lvalue input). +}; + +// ======================================================================================= +// Hook interfaces which must be implemented by the RPC system. Applications never call these +// directly; the RPC system implements them and the types defined earlier in this file wrap them. + +class RequestHook { + // Hook interface implemented by RPC system representing a request being built. + +public: + virtual RemotePromise send() = 0; + // Send the call and return a promise for the result. + + virtual const void* getBrand() = 0; + // Returns a void* that identifies who made this request. This can be used by an RPC adapter to + // discover when tail call is going to be sent over its own connection and therefore can be + // optimized into a remote tail call. + + template + inline static kj::Own from(Request&& request) { + return kj::mv(request.hook); + } +}; + +class ResponseHook { + // Hook interface implemented by RPC system representing a response. + // + // At present this class has no methods. It exists only for garbage collection -- when the + // ResponseHook is destroyed, the results can be freed. + +public: + virtual ~ResponseHook() noexcept(false); + // Just here to make sure the type is dynamic. + + template + inline static kj::Own from(Response&& response) { + return kj::mv(response.hook); + } +}; + +// class PipelineHook is declared in any.h because it is needed there. + +class ClientHook { +public: + ClientHook(); + + virtual Request newCall( + uint64_t interfaceId, uint16_t methodId, kj::Maybe sizeHint) = 0; + // Start a new call, allowing the client to allocate request/response objects as it sees fit. + // This version is used when calls are made from application code in the local process. + + struct VoidPromiseAndPipeline { + kj::Promise promise; + kj::Own pipeline; + }; + + virtual VoidPromiseAndPipeline call(uint64_t interfaceId, uint16_t methodId, + kj::Own&& context) = 0; + // Call the object, but the caller controls allocation of the request/response objects. If the + // callee insists on allocating these objects itself, it must make a copy. This version is used + // when calls come in over the network via an RPC system. Note that even if the returned + // `Promise` is discarded, the call may continue executing if any pipelined calls are + // waiting for it. + // + // Since the caller of this method chooses the CallContext implementation, it is the caller's + // responsibility to ensure that the returned promise is not canceled unless allowed via + // the context's `allowCancellation()`. + // + // The call must not begin synchronously; the callee must arrange for the call to begin in a + // later turn of the event loop. Otherwise, application code may call back and affect the + // callee's state in an unexpected way. + + virtual kj::Maybe getResolved() = 0; + // If this ClientHook is a promise that has already resolved, returns the inner, resolved version + // of the capability. The caller may permanently replace this client with the resolved one if + // desired. Returns null if the client isn't a promise or hasn't resolved yet -- use + // `whenMoreResolved()` to distinguish between them. + + virtual kj::Maybe>> whenMoreResolved() = 0; + // If this client is a settled reference (not a promise), return nullptr. Otherwise, return a + // promise that eventually resolves to a new client that is closer to being the final, settled + // client (i.e. the value eventually returned by `getResolved()`). Calling this repeatedly + // should eventually produce a settled client. + + kj::Promise whenResolved(); + // Repeatedly calls whenMoreResolved() until it returns nullptr. + + virtual kj::Own addRef() = 0; + // Return a new reference to the same capability. + + virtual const void* getBrand() = 0; + // Returns a void* that identifies who made this client. This can be used by an RPC adapter to + // discover when a capability it needs to marshal is one that it created in the first place, and + // therefore it can transfer the capability without proxying. + + static const uint NULL_CAPABILITY_BRAND; + // Value is irrelevant; used for pointer. + + inline bool isNull() { return getBrand() == &NULL_CAPABILITY_BRAND; } + // Returns true if the capability was created as a result of assigning a Client to null or by + // reading a null pointer out of a Cap'n Proto message. + + virtual void* getLocalServer(_::CapabilityServerSetBase& capServerSet); + // If this is a local capability created through `capServerSet`, return the underlying Server. + // Otherwise, return nullptr. Default implementation (which everyone except LocalClient should + // use) always returns nullptr. + + static kj::Own from(Capability::Client client) { return kj::mv(client.hook); } +}; + +class CallContextHook { + // Hook interface implemented by RPC system to manage a call on the server side. See + // CallContext. + +public: + virtual AnyPointer::Reader getParams() = 0; + virtual void releaseParams() = 0; + virtual AnyPointer::Builder getResults(kj::Maybe sizeHint) = 0; + virtual kj::Promise tailCall(kj::Own&& request) = 0; + virtual void allowCancellation() = 0; + + virtual kj::Promise onTailCall() = 0; + // If `tailCall()` is called, resolves to the PipelineHook from the tail call. An + // implementation of `ClientHook::call()` is allowed to call this at most once. + + virtual ClientHook::VoidPromiseAndPipeline directTailCall(kj::Own&& request) = 0; + // Call this when you would otherwise call onTailCall() immediately followed by tailCall(). + // Implementations of tailCall() should typically call directTailCall() and then fulfill the + // promise fulfiller for onTailCall() with the returned pipeline. + + virtual kj::Own addRef() = 0; +}; + +kj::Own newLocalPromiseClient(kj::Promise>&& promise); +// Returns a ClientHook that queues up calls until `promise` resolves, then forwards them to +// the new client. This hook's `getResolved()` and `whenMoreResolved()` methods will reflect the +// redirection to the eventual replacement client. + +kj::Own newLocalPromisePipeline(kj::Promise>&& promise); +// Returns a PipelineHook that queues up calls until `promise` resolves, then forwards them to +// the new pipeline. + +kj::Own newBrokenCap(kj::StringPtr reason); +kj::Own newBrokenCap(kj::Exception&& reason); +// Helper function that creates a capability which simply throws exceptions when called. + +kj::Own newBrokenPipeline(kj::Exception&& reason); +// Helper function that creates a pipeline which simply throws exceptions when called. + +Request newBrokenRequest( + kj::Exception&& reason, kj::Maybe sizeHint); +// Helper function that creates a Request object that simply throws exceptions when sent. + +// ======================================================================================= +// Extend PointerHelpers for interfaces + +namespace _ { // private + +template +struct PointerHelpers { + static inline typename T::Client get(PointerReader reader) { + return typename T::Client(reader.getCapability()); + } + static inline typename T::Client get(PointerBuilder builder) { + return typename T::Client(builder.getCapability()); + } + static inline void set(PointerBuilder builder, typename T::Client&& value) { + builder.setCapability(kj::mv(value.Capability::Client::hook)); + } + static inline void set(PointerBuilder builder, typename T::Client& value) { + builder.setCapability(value.Capability::Client::hook->addRef()); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +} // namespace _ (private) + +// ======================================================================================= +// Extend List for interfaces + +template +struct List { + List() = delete; + + class Reader { + public: + typedef List Reads; + + Reader() = default; + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename T::Client operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return typename T::Client(reader.getPointerElement( + bounded(index) * ELEMENTS).getCapability()); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)) {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename T::Client operator[](uint index) { + KJ_IREQUIRE(index < size()); + return typename T::Client(builder.getPointerElement( + bounded(index) * ELEMENTS).getCapability()); + } + inline void set(uint index, typename T::Client value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).setCapability(kj::mv(value.hook)); + } + inline void adopt(uint index, Orphan&& value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).adopt(kj::mv(value)); + } + inline Orphan disown(uint index) { + KJ_IREQUIRE(index < size()); + return Orphan(builder.getPointerElement(bounded(index) * ELEMENTS).disown()); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(ElementSize::POINTER, bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(ElementSize::POINTER, defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::POINTER, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +// ======================================================================================= +// Inline implementation details + +template +RemotePromise Request::send() { + auto typelessPromise = hook->send(); + hook = nullptr; // prevent reuse + + // Convert the Promise to return the correct response type. + // Explicitly upcast to kj::Promise to make clear that calling .then() doesn't invalidate the + // Pipeline part of the RemotePromise. + auto typedPromise = kj::implicitCast>&>(typelessPromise) + .then([](Response&& response) -> Response { + return Response(response.getAs(), kj::mv(response.hook)); + }); + + // Wrap the typeless pipeline in a typed wrapper. + typename Results::Pipeline typedPipeline( + kj::mv(kj::implicitCast(typelessPromise))); + + return RemotePromise(kj::mv(typedPromise), kj::mv(typedPipeline)); +} + +inline Capability::Client::Client(kj::Own&& hook): hook(kj::mv(hook)) {} +template +inline Capability::Client::Client(kj::Own&& server) + : hook(makeLocalClient(kj::mv(server))) {} +template +inline Capability::Client::Client(kj::Promise&& promise) + : hook(newLocalPromiseClient(promise.then([](T&& t) { return kj::mv(t.hook); }))) {} +inline Capability::Client::Client(Client& other): hook(other.hook->addRef()) {} +inline Capability::Client& Capability::Client::operator=(Client& other) { + hook = other.hook->addRef(); + return *this; +} +template +inline typename T::Client Capability::Client::castAs() { + return typename T::Client(hook->addRef()); +} +inline kj::Promise Capability::Client::whenResolved() { + return hook->whenResolved(); +} +inline Request Capability::Client::typelessRequest( + uint64_t interfaceId, uint16_t methodId, + kj::Maybe sizeHint) { + return newCall(interfaceId, methodId, sizeHint); +} +template +inline Request Capability::Client::newCall( + uint64_t interfaceId, uint16_t methodId, kj::Maybe sizeHint) { + auto typeless = hook->newCall(interfaceId, methodId, sizeHint); + return Request(typeless.template getAs(), kj::mv(typeless.hook)); +} + +template +inline CallContext::CallContext(CallContextHook& hook): hook(&hook) {} +template +inline typename Params::Reader CallContext::getParams() { + return hook->getParams().template getAs(); +} +template +inline void CallContext::releaseParams() { + hook->releaseParams(); +} +template +inline typename Results::Builder CallContext::getResults( + kj::Maybe sizeHint) { + // `template` keyword needed due to: http://llvm.org/bugs/show_bug.cgi?id=17401 + return hook->getResults(sizeHint).template getAs(); +} +template +inline typename Results::Builder CallContext::initResults( + kj::Maybe sizeHint) { + // `template` keyword needed due to: http://llvm.org/bugs/show_bug.cgi?id=17401 + return hook->getResults(sizeHint).template initAs(); +} +template +inline void CallContext::setResults(typename Results::Reader value) { + hook->getResults(value.totalSize()).template setAs(value); +} +template +inline void CallContext::adoptResults(Orphan&& value) { + hook->getResults(nullptr).adopt(kj::mv(value)); +} +template +inline Orphanage CallContext::getResultsOrphanage( + kj::Maybe sizeHint) { + return Orphanage::getForMessageContaining(hook->getResults(sizeHint)); +} +template +template +inline kj::Promise CallContext::tailCall( + Request&& tailRequest) { + return hook->tailCall(kj::mv(tailRequest.hook)); +} +template +inline void CallContext::allowCancellation() { + hook->allowCancellation(); +} + +template +CallContext Capability::Server::internalGetTypedContext( + CallContext typeless) { + return CallContext(*typeless.hook); +} + +Capability::Client Capability::Server::thisCap() { + return Client(thisHook->addRef()); +} + +template +T ReaderCapabilityTable::imbue(T reader) { + return T(_::PointerHelpers>::getInternalReader(reader).imbue(this)); +} + +template +T BuilderCapabilityTable::imbue(T builder) { + return T(_::PointerHelpers>::getInternalBuilder(kj::mv(builder)).imbue(this)); +} + +template +typename T::Client CapabilityServerSet::add(kj::Own&& server) { + void* ptr = reinterpret_cast(server.get()); + // Clang insists that `castAs` is a template-dependent member and therefore we need the + // `template` keyword here, but AFAICT this is wrong: addImpl() is not a template. + return addInternal(kj::mv(server), ptr).template castAs(); +} + +template +kj::Promise> CapabilityServerSet::getLocalServer( + typename T::Client& client) { + return getLocalServerInternal(client) + .then([](void* server) -> kj::Maybe { + if (server == nullptr) { + return nullptr; + } else { + return *reinterpret_cast(server); + } + }); +} + +template +struct Orphanage::GetInnerReader { + static inline kj::Own apply(typename T::Client t) { + return ClientHook::from(kj::mv(t)); + } +}; + +} // namespace capnp + +#endif // CAPNP_CAPABILITY_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/common.h b/phonelibs/capnp-cpp/include/capnp/common.h new file mode 100644 index 00000000000000..3fc7a421124026 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/common.h @@ -0,0 +1,723 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains types which are intended to help detect incorrect usage at compile +// time, but should then be optimized down to basic primitives (usually, integers) by the +// compiler. + +#ifndef CAPNP_COMMON_H_ +#define CAPNP_COMMON_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include +#include + +#if CAPNP_DEBUG_TYPES +#include +#endif + +namespace capnp { + +#define CAPNP_VERSION_MAJOR 0 +#define CAPNP_VERSION_MINOR 6 +#define CAPNP_VERSION_MICRO 1 + +#define CAPNP_VERSION \ + (CAPNP_VERSION_MAJOR * 1000000 + CAPNP_VERSION_MINOR * 1000 + CAPNP_VERSION_MICRO) + +#ifndef CAPNP_LITE +#define CAPNP_LITE 0 +#endif + +typedef unsigned int uint; + +struct Void { + // Type used for Void fields. Using C++'s "void" type creates a bunch of issues since it behaves + // differently from other types. + + inline constexpr bool operator==(Void other) const { return true; } + inline constexpr bool operator!=(Void other) const { return false; } +}; + +static constexpr Void VOID = Void(); +// Constant value for `Void`, which is an empty struct. + +inline kj::StringPtr KJ_STRINGIFY(Void) { return "void"; } + +struct Text; +struct Data; + +enum class Kind: uint8_t { + PRIMITIVE, + BLOB, + ENUM, + STRUCT, + UNION, + INTERFACE, + LIST, + + OTHER + // Some other type which is often a type parameter to Cap'n Proto templates, but which needs + // special handling. This includes types like AnyPointer, Dynamic*, etc. +}; + +enum class Style: uint8_t { + PRIMITIVE, + POINTER, // other than struct + STRUCT, + CAPABILITY +}; + +enum class ElementSize: uint8_t { + // Size of a list element. + + VOID = 0, + BIT = 1, + BYTE = 2, + TWO_BYTES = 3, + FOUR_BYTES = 4, + EIGHT_BYTES = 5, + + POINTER = 6, + + INLINE_COMPOSITE = 7 +}; + +enum class PointerType { + // Various wire types a pointer field can take + + NULL_, + // Should be NULL, but that's #defined in stddef.h + + STRUCT, + LIST, + CAPABILITY +}; + +namespace schemas { + +template +struct EnumInfo; + +} // namespace schemas + +namespace _ { // private + +template struct Kind_; + +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::BLOB; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::BLOB; }; + +template struct Kind_> { + static constexpr Kind kind = Kind::STRUCT; +}; +template struct Kind_> { + static constexpr Kind kind = Kind::INTERFACE; +}; +template struct Kind_::IsEnum>> { + static constexpr Kind kind = Kind::ENUM; +}; + +} // namespace _ (private) + +template ::kind> +inline constexpr Kind kind() { + // This overload of kind() matches types which have a Kind_ specialization. + + return k; +} + +#if _MSC_VER + +#define CAPNP_KIND(T) ::capnp::_::Kind_::kind +// Avoid constexpr methods in MSVC (it remains buggy in many situations). + +#else // _MSC_VER + +#define CAPNP_KIND(T) ::capnp::kind() +// Use this macro rather than kind() in any code which must work in MSVC. + +#endif // _MSC_VER, else + +#if !CAPNP_LITE + +template ()> +inline constexpr Style style() { + return k == Kind::PRIMITIVE || k == Kind::ENUM ? Style::PRIMITIVE + : k == Kind::STRUCT ? Style::STRUCT + : k == Kind::INTERFACE ? Style::CAPABILITY : Style::POINTER; +} + +#endif // !CAPNP_LITE + +template +struct List; + +#if _MSC_VER + +template +struct List {}; +// For some reason, without this declaration, MSVC will error out on some uses of List +// claiming that "T" -- as used in the default initializer for the second template param, "k" -- +// is not defined. I do not understand this error, but adding this empty default declaration fixes +// it. + +#endif + +template struct ListElementType_; +template struct ListElementType_> { typedef T Type; }; +template using ListElementType = typename ListElementType_::Type; + +namespace _ { // private +template struct Kind_> { + static constexpr Kind kind = Kind::LIST; +}; +} // namespace _ (private) + +template struct ReaderFor_ { typedef typename T::Reader Type; }; +template struct ReaderFor_ { typedef T Type; }; +template struct ReaderFor_ { typedef T Type; }; +template struct ReaderFor_ { typedef typename T::Client Type; }; +template using ReaderFor = typename ReaderFor_::Type; +// The type returned by List::Reader::operator[]. + +template struct BuilderFor_ { typedef typename T::Builder Type; }; +template struct BuilderFor_ { typedef T Type; }; +template struct BuilderFor_ { typedef T Type; }; +template struct BuilderFor_ { typedef typename T::Client Type; }; +template using BuilderFor = typename BuilderFor_::Type; +// The type returned by List::Builder::operator[]. + +template struct PipelineFor_ { typedef typename T::Pipeline Type;}; +template struct PipelineFor_ { typedef typename T::Client Type; }; +template using PipelineFor = typename PipelineFor_::Type; + +template struct TypeIfEnum_; +template struct TypeIfEnum_ { typedef T Type; }; + +template +using TypeIfEnum = typename TypeIfEnum_>::Type; + +template +using FromReader = typename kj::Decay::Reads; +// FromReader = MyType (for any Cap'n Proto type). + +template +using FromBuilder = typename kj::Decay::Builds; +// FromBuilder = MyType (for any Cap'n Proto type). + +template +using FromPipeline = typename kj::Decay::Pipelines; +// FromBuilder = MyType (for any Cap'n Proto type). + +template +using FromClient = typename kj::Decay::Calls; +// FromReader = MyType (for any Cap'n Proto interface type). + +template +using FromServer = typename kj::Decay::Serves; +// FromBuilder = MyType (for any Cap'n Proto interface type). + +template +struct FromAny_; + +template +struct FromAny_>> { + using Type = FromReader; +}; + +template +struct FromAny_>> { + using Type = FromBuilder; +}; + +template +struct FromAny_>> { + using Type = FromPipeline; +}; + +// Note that T::Client is covered by FromReader + +template +struct FromAny_, kj::VoidSfinae>> { + using Type = FromServer; +}; + +template +struct FromAny_::kind == Kind::PRIMITIVE || _::Kind_::kind == Kind::ENUM>> { + // TODO(msvc): Ideally the EnableIf condition would be `style() == Style::PRIMITIVE`, but MSVC + // cannot yet use style() in this constexpr context. + + using Type = kj::Decay; +}; + +template +using FromAny = typename FromAny_::Type; +// Given any Cap'n Proto value type as an input, return the Cap'n Proto base type. That is: +// +// Foo::Reader -> Foo +// Foo::Builder -> Foo +// Foo::Pipeline -> Foo +// Foo::Client -> Foo +// Own -> Foo +// uint32_t -> uint32_t + +namespace _ { // private + +template +struct PointerHelpers; + +#if _MSC_VER + +template +struct PointerHelpers {}; +// For some reason, without this declaration, MSVC will error out on some uses of PointerHelpers +// claiming that "T" -- as used in the default initializer for the second template param, "k" -- +// is not defined. I do not understand this error, but adding this empty default declaration fixes +// it. + +#endif + +} // namespace _ (private) + +struct MessageSize { + // Size of a message. Every struct type has a method `.totalSize()` that returns this. + uint64_t wordCount; + uint capCount; +}; + +// ======================================================================================= +// Raw memory types and measures + +using kj::byte; + +class word { uint64_t content KJ_UNUSED_MEMBER; KJ_DISALLOW_COPY(word); public: word() = default; }; +// word is an opaque type with size of 64 bits. This type is useful only to make pointer +// arithmetic clearer. Since the contents are private, the only way to access them is to first +// reinterpret_cast to some other pointer type. +// +// Copying is disallowed because you should always use memcpy(). Otherwise, you may run afoul of +// aliasing rules. +// +// A pointer of type word* should always be word-aligned even if won't actually be dereferenced as +// that type. + +static_assert(sizeof(byte) == 1, "uint8_t is not one byte?"); +static_assert(sizeof(word) == 8, "uint64_t is not 8 bytes?"); + +#if CAPNP_DEBUG_TYPES +// Set CAPNP_DEBUG_TYPES to 1 to use kj::Quantity for "count" types. Otherwise, plain integers are +// used. All the code should still operate exactly the same, we just lose compile-time checking. +// Note that this will also change symbol names, so it's important that the library and any clients +// be compiled with the same setting here. +// +// We disable this by default to reduce symbol name size and avoid any possibility of the compiler +// failing to fully-optimize the types, but anyone modifying Cap'n Proto itself should enable this +// during development and testing. + +namespace _ { class BitLabel; class ElementLabel; struct WirePointer; } + +template +using BitCountN = kj::Quantity(), T>, _::BitLabel>; +template +using ByteCountN = kj::Quantity(), T>, byte>; +template +using WordCountN = kj::Quantity(), T>, word>; +template +using ElementCountN = kj::Quantity(), T>, _::ElementLabel>; +template +using WirePointerCountN = kj::Quantity(), T>, _::WirePointer>; + +typedef BitCountN<8, uint8_t> BitCount8; +typedef BitCountN<16, uint16_t> BitCount16; +typedef BitCountN<32, uint32_t> BitCount32; +typedef BitCountN<64, uint64_t> BitCount64; +typedef BitCountN BitCount; + +typedef ByteCountN<8, uint8_t> ByteCount8; +typedef ByteCountN<16, uint16_t> ByteCount16; +typedef ByteCountN<32, uint32_t> ByteCount32; +typedef ByteCountN<64, uint64_t> ByteCount64; +typedef ByteCountN ByteCount; + +typedef WordCountN<8, uint8_t> WordCount8; +typedef WordCountN<16, uint16_t> WordCount16; +typedef WordCountN<32, uint32_t> WordCount32; +typedef WordCountN<64, uint64_t> WordCount64; +typedef WordCountN WordCount; + +typedef ElementCountN<8, uint8_t> ElementCount8; +typedef ElementCountN<16, uint16_t> ElementCount16; +typedef ElementCountN<32, uint32_t> ElementCount32; +typedef ElementCountN<64, uint64_t> ElementCount64; +typedef ElementCountN ElementCount; + +typedef WirePointerCountN<8, uint8_t> WirePointerCount8; +typedef WirePointerCountN<16, uint16_t> WirePointerCount16; +typedef WirePointerCountN<32, uint32_t> WirePointerCount32; +typedef WirePointerCountN<64, uint64_t> WirePointerCount64; +typedef WirePointerCountN WirePointerCount; + +template +using BitsPerElementN = decltype(BitCountN() / ElementCountN()); +template +using BytesPerElementN = decltype(ByteCountN() / ElementCountN()); +template +using WordsPerElementN = decltype(WordCountN() / ElementCountN()); +template +using PointersPerElementN = decltype(WirePointerCountN() / ElementCountN()); + +using kj::bounded; +using kj::unbound; +using kj::unboundAs; +using kj::unboundMax; +using kj::unboundMaxBits; +using kj::assertMax; +using kj::assertMaxBits; +using kj::upgradeBound; +using kj::ThrowOverflow; +using kj::assumeBits; +using kj::assumeMax; +using kj::subtractChecked; +using kj::trySubtract; + +template +inline constexpr U* operator+(U* ptr, kj::Quantity offset) { + return ptr + unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator+(const U* ptr, kj::Quantity offset) { + return ptr + unbound(offset / kj::unit>()); +} +template +inline constexpr U* operator+=(U*& ptr, kj::Quantity offset) { + return ptr = ptr + unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator+=(const U*& ptr, kj::Quantity offset) { + return ptr = ptr + unbound(offset / kj::unit>()); +} + +template +inline constexpr U* operator-(U* ptr, kj::Quantity offset) { + return ptr - unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator-(const U* ptr, kj::Quantity offset) { + return ptr - unbound(offset / kj::unit>()); +} +template +inline constexpr U* operator-=(U*& ptr, kj::Quantity offset) { + return ptr = ptr - unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator-=(const U*& ptr, kj::Quantity offset) { + return ptr = ptr - unbound(offset / kj::unit>()); +} + +constexpr auto BITS = kj::unit>(); +constexpr auto BYTES = kj::unit>(); +constexpr auto WORDS = kj::unit>(); +constexpr auto ELEMENTS = kj::unit>(); +constexpr auto POINTERS = kj::unit>(); + +constexpr auto ZERO = kj::bounded<0>(); +constexpr auto ONE = kj::bounded<1>(); + +// GCC 4.7 actually gives unused warnings on these constants in opt mode... +constexpr auto BITS_PER_BYTE KJ_UNUSED = bounded<8>() * BITS / BYTES; +constexpr auto BITS_PER_WORD KJ_UNUSED = bounded<64>() * BITS / WORDS; +constexpr auto BYTES_PER_WORD KJ_UNUSED = bounded<8>() * BYTES / WORDS; + +constexpr auto BITS_PER_POINTER KJ_UNUSED = bounded<64>() * BITS / POINTERS; +constexpr auto BYTES_PER_POINTER KJ_UNUSED = bounded<8>() * BYTES / POINTERS; +constexpr auto WORDS_PER_POINTER KJ_UNUSED = ONE * WORDS / POINTERS; + +constexpr auto POINTER_SIZE_IN_WORDS = ONE * POINTERS * WORDS_PER_POINTER; + +constexpr uint SEGMENT_WORD_COUNT_BITS = 29; // Number of words in a segment. +constexpr uint LIST_ELEMENT_COUNT_BITS = 29; // Number of elements in a list. +constexpr uint STRUCT_DATA_WORD_COUNT_BITS = 16; // Number of words in a Struct data section. +constexpr uint STRUCT_POINTER_COUNT_BITS = 16; // Number of pointers in a Struct pointer section. +constexpr uint BLOB_SIZE_BITS = 29; // Number of bytes in a blob. + +typedef WordCountN SegmentWordCount; +typedef ElementCountN ListElementCount; +typedef WordCountN StructDataWordCount; +typedef WirePointerCountN StructPointerCount; +typedef ByteCountN BlobSize; + +constexpr auto MAX_SEGMENT_WORDS = + bounded()>() * WORDS; +constexpr auto MAX_LIST_ELEMENTS = + bounded()>() * ELEMENTS; +constexpr auto MAX_STUCT_DATA_WORDS = + bounded()>() * WORDS; +constexpr auto MAX_STRUCT_POINTER_COUNT = + bounded()>() * POINTERS; + +using StructDataBitCount = decltype(WordCountN() * BITS_PER_WORD); +// Number of bits in a Struct data segment (should come out to BitCountN<22>). + +using StructDataOffset = decltype(StructDataBitCount() * (ONE * ELEMENTS / BITS)); +using StructPointerOffset = StructPointerCount; +// Type of a field offset. + +inline StructDataOffset assumeDataOffset(uint32_t offset) { + return assumeMax(MAX_STUCT_DATA_WORDS * BITS_PER_WORD * (ONE * ELEMENTS / BITS), + bounded(offset) * ELEMENTS); +} + +inline StructPointerOffset assumePointerOffset(uint32_t offset) { + return assumeMax(MAX_STRUCT_POINTER_COUNT, bounded(offset) * POINTERS); +} + +constexpr uint MAX_TEXT_SIZE = kj::maxValueForBits() - 1; +typedef kj::Quantity, byte> TextSize; +// Not including NUL terminator. + +template +inline KJ_CONSTEXPR() decltype(bounded() * BYTES / ELEMENTS) bytesPerElement() { + return bounded() * BYTES / ELEMENTS; +} + +template +inline KJ_CONSTEXPR() decltype(bounded() * BITS / ELEMENTS) bitsPerElement() { + return bounded() * BITS / ELEMENTS; +} + +template +inline constexpr kj::Quantity, T> +intervalLength(const T* a, const T* b, kj::Quantity, T>) { + return kj::assumeMax(b - a) * kj::unit, T>>(); +} + +template +inline constexpr kj::ArrayPtr arrayPtr(const U* ptr, kj::Quantity size) { + return kj::ArrayPtr(ptr, unbound(size / kj::unit>())); +} +template +inline constexpr kj::ArrayPtr arrayPtr(U* ptr, kj::Quantity size) { + return kj::ArrayPtr(ptr, unbound(size / kj::unit>())); +} + +#else + +template +using BitCountN = T; +template +using ByteCountN = T; +template +using WordCountN = T; +template +using ElementCountN = T; +template +using WirePointerCountN = T; + + +// XXX +typedef BitCountN<8, uint8_t> BitCount8; +typedef BitCountN<16, uint16_t> BitCount16; +typedef BitCountN<32, uint32_t> BitCount32; +typedef BitCountN<64, uint64_t> BitCount64; +typedef BitCountN BitCount; + +typedef ByteCountN<8, uint8_t> ByteCount8; +typedef ByteCountN<16, uint16_t> ByteCount16; +typedef ByteCountN<32, uint32_t> ByteCount32; +typedef ByteCountN<64, uint64_t> ByteCount64; +typedef ByteCountN ByteCount; + +typedef WordCountN<8, uint8_t> WordCount8; +typedef WordCountN<16, uint16_t> WordCount16; +typedef WordCountN<32, uint32_t> WordCount32; +typedef WordCountN<64, uint64_t> WordCount64; +typedef WordCountN WordCount; + +typedef ElementCountN<8, uint8_t> ElementCount8; +typedef ElementCountN<16, uint16_t> ElementCount16; +typedef ElementCountN<32, uint32_t> ElementCount32; +typedef ElementCountN<64, uint64_t> ElementCount64; +typedef ElementCountN ElementCount; + +typedef WirePointerCountN<8, uint8_t> WirePointerCount8; +typedef WirePointerCountN<16, uint16_t> WirePointerCount16; +typedef WirePointerCountN<32, uint32_t> WirePointerCount32; +typedef WirePointerCountN<64, uint64_t> WirePointerCount64; +typedef WirePointerCountN WirePointerCount; + +template +using BitsPerElementN = decltype(BitCountN() / ElementCountN()); +template +using BytesPerElementN = decltype(ByteCountN() / ElementCountN()); +template +using WordsPerElementN = decltype(WordCountN() / ElementCountN()); +template +using PointersPerElementN = decltype(WirePointerCountN() / ElementCountN()); + +using kj::ThrowOverflow; +// YYY + +template inline constexpr uint bounded() { return i; } +template inline constexpr T bounded(T i) { return i; } +template inline constexpr T unbound(T i) { return i; } + +template inline constexpr T unboundAs(U i) { return i; } + +template inline constexpr uint unboundMax(T i) { return i; } +template inline constexpr uint unboundMaxBits(T i) { return i; } + +template +inline T assertMax(T value, ErrorFunc&& func) { + if (KJ_UNLIKELY(value > newMax)) func(); + return value; +} + +template +inline T assertMax(uint newMax, T value, ErrorFunc&& func) { + if (KJ_UNLIKELY(value > newMax)) func(); + return value; +} + +template +inline T assertMaxBits(T value, ErrorFunc&& func = ErrorFunc()) { + if (KJ_UNLIKELY(value > kj::maxValueForBits())) func(); + return value; +} + +template +inline T assertMaxBits(uint bits, T value, ErrorFunc&& func = ErrorFunc()) { + if (KJ_UNLIKELY(value > (1ull << bits) - 1)) func(); + return value; +} + +template inline constexpr T upgradeBound(U i) { return i; } + +template inline constexpr T assumeBits(T i) { return i; } +template inline constexpr T assumeMax(T i) { return i; } + +template +inline auto subtractChecked(T a, U b, ErrorFunc&& errorFunc = ErrorFunc()) + -> decltype(a - b) { + if (b > a) errorFunc(); + return a - b; +} + +template +inline auto trySubtract(T a, U b) -> kj::Maybe { + if (b > a) { + return nullptr; + } else { + return a - b; + } +} + +constexpr uint BITS = 1; +constexpr uint BYTES = 1; +constexpr uint WORDS = 1; +constexpr uint ELEMENTS = 1; +constexpr uint POINTERS = 1; + +constexpr uint ZERO = 0; +constexpr uint ONE = 1; + +// GCC 4.7 actually gives unused warnings on these constants in opt mode... +constexpr uint BITS_PER_BYTE KJ_UNUSED = 8; +constexpr uint BITS_PER_WORD KJ_UNUSED = 64; +constexpr uint BYTES_PER_WORD KJ_UNUSED = 8; + +constexpr uint BITS_PER_POINTER KJ_UNUSED = 64; +constexpr uint BYTES_PER_POINTER KJ_UNUSED = 8; +constexpr uint WORDS_PER_POINTER KJ_UNUSED = 1; + +// XXX +constexpr uint POINTER_SIZE_IN_WORDS = ONE * POINTERS * WORDS_PER_POINTER; + +constexpr uint SEGMENT_WORD_COUNT_BITS = 29; // Number of words in a segment. +constexpr uint LIST_ELEMENT_COUNT_BITS = 29; // Number of elements in a list. +constexpr uint STRUCT_DATA_WORD_COUNT_BITS = 16; // Number of words in a Struct data section. +constexpr uint STRUCT_POINTER_COUNT_BITS = 16; // Number of pointers in a Struct pointer section. +constexpr uint BLOB_SIZE_BITS = 29; // Number of bytes in a blob. + +typedef WordCountN SegmentWordCount; +typedef ElementCountN ListElementCount; +typedef WordCountN StructDataWordCount; +typedef WirePointerCountN StructPointerCount; +typedef ByteCountN BlobSize; +// YYY + +constexpr auto MAX_SEGMENT_WORDS = kj::maxValueForBits(); +constexpr auto MAX_LIST_ELEMENTS = kj::maxValueForBits(); +constexpr auto MAX_STUCT_DATA_WORDS = kj::maxValueForBits(); +constexpr auto MAX_STRUCT_POINTER_COUNT = kj::maxValueForBits(); + +typedef uint StructDataBitCount; +typedef uint StructDataOffset; +typedef uint StructPointerOffset; + +inline StructDataOffset assumeDataOffset(uint32_t offset) { return offset; } +inline StructPointerOffset assumePointerOffset(uint32_t offset) { return offset; } + +constexpr uint MAX_TEXT_SIZE = kj::maxValueForBits() - 1; +typedef uint TextSize; + +template +inline KJ_CONSTEXPR() size_t bytesPerElement() { return sizeof(T); } + +template +inline KJ_CONSTEXPR() size_t bitsPerElement() { return sizeof(T) * 8; } + +template +inline constexpr ptrdiff_t intervalLength(const T* a, const T* b, uint) { + return b - a; +} + +template +inline constexpr kj::ArrayPtr arrayPtr(const U* ptr, T size) { + return kj::arrayPtr(ptr, size); +} +template +inline constexpr kj::ArrayPtr arrayPtr(U* ptr, T size) { + return kj::arrayPtr(ptr, size); +} + +#endif + +} // namespace capnp + +#endif // CAPNP_COMMON_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/compat/json.capnp.h b/phonelibs/capnp-cpp/include/capnp/compat/json.capnp.h new file mode 100644 index 00000000000000..a8877e540b9f2a --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/compat/json.capnp.h @@ -0,0 +1,860 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: json.capnp + +#ifndef CAPNP_INCLUDED_8ef99297a43a5e34_ +#define CAPNP_INCLUDED_8ef99297a43a5e34_ + +#include +#if !CAPNP_LITE +#include +#endif // !CAPNP_LITE + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(8825ffaa852cda72); +CAPNP_DECLARE_SCHEMA(c27855d853a937cc); +CAPNP_DECLARE_SCHEMA(9bbf84153dd4bb60); + +} // namespace schemas +} // namespace capnp + +namespace capnp { + +struct JsonValue { + JsonValue() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + NULL_, + BOOLEAN, + NUMBER, + STRING, + ARRAY, + OBJECT, + CALL, + }; + struct Field; + struct Call; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8825ffaa852cda72, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JsonValue::Field { + Field() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c27855d853a937cc, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JsonValue::Call { + Call() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9bbf84153dd4bb60, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class JsonValue::Reader { +public: + typedef JsonValue Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isNull() const; + inline ::capnp::Void getNull() const; + + inline bool isBoolean() const; + inline bool getBoolean() const; + + inline bool isNumber() const; + inline double getNumber() const; + + inline bool isString() const; + inline bool hasString() const; + inline ::capnp::Text::Reader getString() const; + + inline bool isArray() const; + inline bool hasArray() const; + inline ::capnp::List< ::capnp::JsonValue>::Reader getArray() const; + + inline bool isObject() const; + inline bool hasObject() const; + inline ::capnp::List< ::capnp::JsonValue::Field>::Reader getObject() const; + + inline bool isCall() const; + inline bool hasCall() const; + inline ::capnp::JsonValue::Call::Reader getCall() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JsonValue::Builder { +public: + typedef JsonValue Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isNull(); + inline ::capnp::Void getNull(); + inline void setNull( ::capnp::Void value = ::capnp::VOID); + + inline bool isBoolean(); + inline bool getBoolean(); + inline void setBoolean(bool value); + + inline bool isNumber(); + inline double getNumber(); + inline void setNumber(double value); + + inline bool isString(); + inline bool hasString(); + inline ::capnp::Text::Builder getString(); + inline void setString( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initString(unsigned int size); + inline void adoptString(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownString(); + + inline bool isArray(); + inline bool hasArray(); + inline ::capnp::List< ::capnp::JsonValue>::Builder getArray(); + inline void setArray( ::capnp::List< ::capnp::JsonValue>::Reader value); + inline ::capnp::List< ::capnp::JsonValue>::Builder initArray(unsigned int size); + inline void adoptArray(::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> disownArray(); + + inline bool isObject(); + inline bool hasObject(); + inline ::capnp::List< ::capnp::JsonValue::Field>::Builder getObject(); + inline void setObject( ::capnp::List< ::capnp::JsonValue::Field>::Reader value); + inline ::capnp::List< ::capnp::JsonValue::Field>::Builder initObject(unsigned int size); + inline void adoptObject(::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>> disownObject(); + + inline bool isCall(); + inline bool hasCall(); + inline ::capnp::JsonValue::Call::Builder getCall(); + inline void setCall( ::capnp::JsonValue::Call::Reader value); + inline ::capnp::JsonValue::Call::Builder initCall(); + inline void adoptCall(::capnp::Orphan< ::capnp::JsonValue::Call>&& value); + inline ::capnp::Orphan< ::capnp::JsonValue::Call> disownCall(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JsonValue::Pipeline { +public: + typedef JsonValue Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JsonValue::Field::Reader { +public: + typedef Field Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline bool hasValue() const; + inline ::capnp::JsonValue::Reader getValue() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JsonValue::Field::Builder { +public: + typedef Field Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline bool hasValue(); + inline ::capnp::JsonValue::Builder getValue(); + inline void setValue( ::capnp::JsonValue::Reader value); + inline ::capnp::JsonValue::Builder initValue(); + inline void adoptValue(::capnp::Orphan< ::capnp::JsonValue>&& value); + inline ::capnp::Orphan< ::capnp::JsonValue> disownValue(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JsonValue::Field::Pipeline { +public: + typedef Field Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::JsonValue::Pipeline getValue(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JsonValue::Call::Reader { +public: + typedef Call Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasFunction() const; + inline ::capnp::Text::Reader getFunction() const; + + inline bool hasParams() const; + inline ::capnp::List< ::capnp::JsonValue>::Reader getParams() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JsonValue::Call::Builder { +public: + typedef Call Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasFunction(); + inline ::capnp::Text::Builder getFunction(); + inline void setFunction( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initFunction(unsigned int size); + inline void adoptFunction(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownFunction(); + + inline bool hasParams(); + inline ::capnp::List< ::capnp::JsonValue>::Builder getParams(); + inline void setParams( ::capnp::List< ::capnp::JsonValue>::Reader value); + inline ::capnp::List< ::capnp::JsonValue>::Builder initParams(unsigned int size); + inline void adoptParams(::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> disownParams(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JsonValue::Call::Pipeline { +public: + typedef Call Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::JsonValue::Which JsonValue::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::JsonValue::Which JsonValue::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool JsonValue::Reader::isNull() const { + return which() == JsonValue::NULL_; +} +inline bool JsonValue::Builder::isNull() { + return which() == JsonValue::NULL_; +} +inline ::capnp::Void JsonValue::Reader::getNull() const { + KJ_IREQUIRE((which() == JsonValue::NULL_), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void JsonValue::Builder::getNull() { + KJ_IREQUIRE((which() == JsonValue::NULL_), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void JsonValue::Builder::setNull( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::NULL_); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool JsonValue::Reader::isBoolean() const { + return which() == JsonValue::BOOLEAN; +} +inline bool JsonValue::Builder::isBoolean() { + return which() == JsonValue::BOOLEAN; +} +inline bool JsonValue::Reader::getBoolean() const { + KJ_IREQUIRE((which() == JsonValue::BOOLEAN), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} + +inline bool JsonValue::Builder::getBoolean() { + KJ_IREQUIRE((which() == JsonValue::BOOLEAN), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} +inline void JsonValue::Builder::setBoolean(bool value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::BOOLEAN); + _builder.setDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS, value); +} + +inline bool JsonValue::Reader::isNumber() const { + return which() == JsonValue::NUMBER; +} +inline bool JsonValue::Builder::isNumber() { + return which() == JsonValue::NUMBER; +} +inline double JsonValue::Reader::getNumber() const { + KJ_IREQUIRE((which() == JsonValue::NUMBER), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double JsonValue::Builder::getNumber() { + KJ_IREQUIRE((which() == JsonValue::NUMBER), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void JsonValue::Builder::setNumber(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::NUMBER); + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool JsonValue::Reader::isString() const { + return which() == JsonValue::STRING; +} +inline bool JsonValue::Builder::isString() { + return which() == JsonValue::STRING; +} +inline bool JsonValue::Reader::hasString() const { + if (which() != JsonValue::STRING) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasString() { + if (which() != JsonValue::STRING) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader JsonValue::Reader::getString() const { + KJ_IREQUIRE((which() == JsonValue::STRING), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder JsonValue::Builder::getString() { + KJ_IREQUIRE((which() == JsonValue::STRING), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setString( ::capnp::Text::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::STRING); + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder JsonValue::Builder::initString(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::STRING); + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Builder::adoptString( + ::capnp::Orphan< ::capnp::Text>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::STRING); + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> JsonValue::Builder::disownString() { + KJ_IREQUIRE((which() == JsonValue::STRING), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Reader::isArray() const { + return which() == JsonValue::ARRAY; +} +inline bool JsonValue::Builder::isArray() { + return which() == JsonValue::ARRAY; +} +inline bool JsonValue::Reader::hasArray() const { + if (which() != JsonValue::ARRAY) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasArray() { + if (which() != JsonValue::ARRAY) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::JsonValue>::Reader JsonValue::Reader::getArray() const { + KJ_IREQUIRE((which() == JsonValue::ARRAY), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Builder::getArray() { + KJ_IREQUIRE((which() == JsonValue::ARRAY), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setArray( ::capnp::List< ::capnp::JsonValue>::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::ARRAY); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Builder::initArray(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::ARRAY); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Builder::adoptArray( + ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::ARRAY); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> JsonValue::Builder::disownArray() { + KJ_IREQUIRE((which() == JsonValue::ARRAY), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Reader::isObject() const { + return which() == JsonValue::OBJECT; +} +inline bool JsonValue::Builder::isObject() { + return which() == JsonValue::OBJECT; +} +inline bool JsonValue::Reader::hasObject() const { + if (which() != JsonValue::OBJECT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasObject() { + if (which() != JsonValue::OBJECT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::JsonValue::Field>::Reader JsonValue::Reader::getObject() const { + KJ_IREQUIRE((which() == JsonValue::OBJECT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::JsonValue::Field>::Builder JsonValue::Builder::getObject() { + KJ_IREQUIRE((which() == JsonValue::OBJECT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setObject( ::capnp::List< ::capnp::JsonValue::Field>::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::OBJECT); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::JsonValue::Field>::Builder JsonValue::Builder::initObject(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::OBJECT); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Builder::adoptObject( + ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::OBJECT); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>> JsonValue::Builder::disownObject() { + KJ_IREQUIRE((which() == JsonValue::OBJECT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Reader::isCall() const { + return which() == JsonValue::CALL; +} +inline bool JsonValue::Builder::isCall() { + return which() == JsonValue::CALL; +} +inline bool JsonValue::Reader::hasCall() const { + if (which() != JsonValue::CALL) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasCall() { + if (which() != JsonValue::CALL) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::JsonValue::Call::Reader JsonValue::Reader::getCall() const { + KJ_IREQUIRE((which() == JsonValue::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::JsonValue::Call::Builder JsonValue::Builder::getCall() { + KJ_IREQUIRE((which() == JsonValue::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setCall( ::capnp::JsonValue::Call::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::CALL); + ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::JsonValue::Call::Builder JsonValue::Builder::initCall() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::CALL); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::adoptCall( + ::capnp::Orphan< ::capnp::JsonValue::Call>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::CALL); + ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::JsonValue::Call> JsonValue::Builder::disownCall() { + KJ_IREQUIRE((which() == JsonValue::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Field::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Field::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader JsonValue::Field::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder JsonValue::Field::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Field::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder JsonValue::Field::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Field::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> JsonValue::Field::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Field::Reader::hasValue() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Field::Builder::hasValue() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::JsonValue::Reader JsonValue::Field::Reader::getValue() const { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::JsonValue::Builder JsonValue::Field::Builder::getValue() { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::JsonValue::Pipeline JsonValue::Field::Pipeline::getValue() { + return ::capnp::JsonValue::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void JsonValue::Field::Builder::setValue( ::capnp::JsonValue::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::JsonValue>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::JsonValue::Builder JsonValue::Field::Builder::initValue() { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void JsonValue::Field::Builder::adoptValue( + ::capnp::Orphan< ::capnp::JsonValue>&& value) { + ::capnp::_::PointerHelpers< ::capnp::JsonValue>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::JsonValue> JsonValue::Field::Builder::disownValue() { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Call::Reader::hasFunction() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Call::Builder::hasFunction() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader JsonValue::Call::Reader::getFunction() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder JsonValue::Call::Builder::getFunction() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Call::Builder::setFunction( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder JsonValue::Call::Builder::initFunction(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Call::Builder::adoptFunction( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> JsonValue::Call::Builder::disownFunction() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Call::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Call::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::JsonValue>::Reader JsonValue::Call::Reader::getParams() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Call::Builder::getParams() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void JsonValue::Call::Builder::setParams( ::capnp::List< ::capnp::JsonValue>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Call::Builder::initParams(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Call::Builder::adoptParams( + ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> JsonValue::Call::Builder::disownParams() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +} // namespace + +#endif // CAPNP_INCLUDED_8ef99297a43a5e34_ diff --git a/phonelibs/capnp-cpp/include/capnp/compat/json.h b/phonelibs/capnp-cpp/include/capnp/compat/json.h new file mode 100644 index 00000000000000..7fa815e0998e9e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/compat/json.h @@ -0,0 +1,462 @@ +// Copyright (c) 2015 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_COMPAT_JSON_H_ +#define CAPNP_COMPAT_JSON_H_ + +#include +#include +#include + +namespace capnp { + +class JsonCodec { + // Flexible class for encoding Cap'n Proto types as JSON, and decoding JSON back to Cap'n Proto. + // + // Typical usage: + // + // JsonCodec json; + // + // // encode + // kj::String encoded = json.encode(someStructReader); + // + // // decode + // json.decode(encoded, someStructBuilder); + // + // Advanced users can do fancy things like override the way certain types or fields are + // represented in JSON by registering handlers. See the unit test for an example. + // + // Notes: + // - When encoding, all primitive fields are always encoded, even if default-valued. Pointer + // fields are only encoded if they are non-null. + // - 64-bit integers are encoded as strings, since JSON "numbers" are double-precision floating + // points which cannot store a 64-bit integer without losing data. + // - NaNs and infinite floating point numbers are not allowed by the JSON spec, and so are encoded + // as null. This matches the behavior of `JSON.stringify` in at least Firefox and Chrome. + // - Data is encoded as an array of numbers in the range [0,255]. You probably want to register + // a handler that does something better, like maybe base64 encoding, but there are a zillion + // different ways people do this. + // - Encoding/decoding capabilities and AnyPointers requires registering a Handler, since there's + // no obvious default behavior. + // - When decoding, unrecognized field names are ignored. Note: This means that JSON is NOT a + // good format for receiving input from a human. Consider `capnp eval` or the SchemaParser + // library for human input. + +public: + JsonCodec(); + ~JsonCodec() noexcept(false); + + // --------------------------------------------------------------------------- + // standard API + + void setPrettyPrint(bool enabled); + // Enable to insert newlines, indentation, and other extra spacing into the output. The default + // is to use minimal whitespace. + + void setMaxNestingDepth(size_t maxNestingDepth); + // Set maximum nesting depth when decoding JSON to prevent highly nested input from overflowing + // the call stack. The default is 64. + + template + kj::String encode(T&& value); + // Encode any Cap'n Proto value to JSON, including primitives and + // Dynamic{Enum,Struct,List,Capability}, but not DynamicValue (see below). + + kj::String encode(DynamicValue::Reader value, Type type) const; + // Encode a DynamicValue to JSON. `type` is needed because `DynamicValue` itself does + // not distinguish between e.g. int32 and int64, which in JSON are handled differently. Most + // of the time, though, you can use the single-argument templated version of `encode()` instead. + + void decode(kj::ArrayPtr input, DynamicStruct::Builder output) const; + // Decode JSON text directly into a struct builder. This only works for structs since lists + // need to be allocated with the correct size in advance. + // + // (Remember that any Cap'n Proto struct reader type can be implicitly cast to + // DynamicStruct::Reader.) + + template + Orphan decode(kj::ArrayPtr input, Orphanage orphanage) const; + // Decode JSON text to any Cap'n Proto object (pointer value), allocated using the given + // orphanage. T must be specified explicitly and cannot be dynamic, e.g.: + // + // Orphan orphan = json.decode(text, orphanage); + + template + ReaderFor decode(kj::ArrayPtr input) const; + // Decode JSON text into a primitive or capability value. T must be specified explicitly and + // cannot be dynamic, e.g.: + // + // uint32_t n = json.decode(text); + + Orphan decode(kj::ArrayPtr input, Type type, Orphanage orphanage) const; + Orphan decode( + kj::ArrayPtr input, ListSchema type, Orphanage orphanage) const; + Orphan decode( + kj::ArrayPtr input, StructSchema type, Orphanage orphanage) const; + DynamicCapability::Client decode(kj::ArrayPtr input, InterfaceSchema type) const; + DynamicEnum decode(kj::ArrayPtr input, EnumSchema type) const; + // Decode to a dynamic value, specifying the type schema. + + // --------------------------------------------------------------------------- + // layered API + // + // You can separate text <-> JsonValue from JsonValue <-> T. These are particularly useful + // for calling from Handler implementations. + + kj::String encodeRaw(JsonValue::Reader value) const; + void decodeRaw(kj::ArrayPtr input, JsonValue::Builder output) const; + // Translate JsonValue <-> text. + + template + void encode(T&& value, JsonValue::Builder output); + void encode(DynamicValue::Reader input, Type type, JsonValue::Builder output) const; + void decode(JsonValue::Reader input, DynamicStruct::Builder output) const; + template + Orphan decode(JsonValue::Reader input, Orphanage orphanage) const; + template + ReaderFor decode(JsonValue::Reader input) const; + + Orphan decode(JsonValue::Reader input, Type type, Orphanage orphanage) const; + Orphan decode(JsonValue::Reader input, ListSchema type, Orphanage orphanage) const; + Orphan decode( + JsonValue::Reader input, StructSchema type, Orphanage orphanage) const; + DynamicCapability::Client decode(JsonValue::Reader input, InterfaceSchema type) const; + DynamicEnum decode(JsonValue::Reader input, EnumSchema type) const; + + // --------------------------------------------------------------------------- + // specializing particular types + + template ()> + class Handler; + // Implement this interface to specify a special encoding for a particular type or field. + // + // The templates are a bit ugly, but subclasses of this type essentially implement two methods, + // one to encode values of this type and one to decode values of this type. `encode()` is simple: + // + // void encode(const JsonCodec& codec, ReaderFor input, JsonValue::Builder output) const; + // + // `decode()` is a bit trickier. When T is a struct (including DynamicStruct), it is: + // + // void decode(const JsonCodec& codec, JsonValue::Reader input, BuilderFor output) const; + // + // However, when T is a primitive, decode() is: + // + // T decode(const JsonCodec& codec, JsonValue::Reader input) const; + // + // Or when T is any non-struct object (list, blob), decode() is: + // + // Orphan decode(const JsonCodec& codec, JsonValue::Reader input, Orphanage orphanage) const; + // + // Or when T is an interface: + // + // T::Client decode(const JsonCodec& codec, JsonValue::Reader input) const; + // + // Additionally, when T is a struct you can *optionally* also implement the orphan-returning form + // of decode(), but it will only be called when the struct would be allocated as an individual + // object, not as part of a list. This allows you to return "nullptr" in these cases to say that + // the pointer value should be null. This does not apply to list elements because struct list + // elements cannot ever be null (since Cap'n Proto encodes struct lists as a flat list rather + // than list-of-pointers). + + template + void addTypeHandler(Handler& handler); + void addTypeHandler(Type type, Handler& handler); + void addTypeHandler(EnumSchema type, Handler& handler); + void addTypeHandler(StructSchema type, Handler& handler); + void addTypeHandler(ListSchema type, Handler& handler); + void addTypeHandler(InterfaceSchema type, Handler& handler); + // Arrange that whenever the type T appears in the message, your handler will be used to + // encode/decode it. + // + // Note that if you register a handler for a capability type, it will also apply to subtypes. + // Thus Handler handles all capabilities. + + template + void addFieldHandler(StructSchema::Field field, Handler& handler); + // Matches only the specific field. T can be a dynamic type. T must match the field's type. + +private: + class HandlerBase; + struct Impl; + + kj::Own impl; + + void encodeField(StructSchema::Field field, DynamicValue::Reader input, + JsonValue::Builder output) const; + void decodeArray(List::Reader input, DynamicList::Builder output) const; + void decodeObject(List::Reader input, DynamicStruct::Builder output) const; + void addTypeHandlerImpl(Type type, HandlerBase& handler); + void addFieldHandlerImpl(StructSchema::Field field, Type type, HandlerBase& handler); +}; + +// ======================================================================================= +// inline implementation details + +template +kj::String JsonCodec::encode(T&& value) { + typedef FromAny> Base; + return encode(DynamicValue::Reader(ReaderFor(kj::fwd(value))), Type::from()); +} + +template +inline Orphan JsonCodec::decode(kj::ArrayPtr input, Orphanage orphanage) const { + return decode(input, Type::from(), orphanage).template releaseAs(); +} + +template +inline ReaderFor JsonCodec::decode(kj::ArrayPtr input) const { + static_assert(style() == Style::PRIMITIVE || style() == Style::CAPABILITY, + "must specify an orphanage to decode an object type"); + return decode(input, Type::from(), Orphanage()).getReader().template as(); +} + +inline Orphan JsonCodec::decode( + kj::ArrayPtr input, ListSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline Orphan JsonCodec::decode( + kj::ArrayPtr input, StructSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline DynamicCapability::Client JsonCodec::decode( + kj::ArrayPtr input, InterfaceSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} +inline DynamicEnum JsonCodec::decode(kj::ArrayPtr input, EnumSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} + +// ----------------------------------------------------------------------------- + +template +void JsonCodec::encode(T&& value, JsonValue::Builder output) { + typedef FromAny> Base; + encode(DynamicValue::Reader(ReaderFor(kj::fwd(value))), Type::from(), output); +} + +template +inline Orphan JsonCodec::decode(JsonValue::Reader input, Orphanage orphanage) const { + return decode(input, Type::from(), orphanage).template releaseAs(); +} + +template +inline ReaderFor JsonCodec::decode(JsonValue::Reader input) const { + static_assert(style() == Style::PRIMITIVE || style() == Style::CAPABILITY, + "must specify an orphanage to decode an object type"); + return decode(input, Type::from(), Orphanage()).getReader().template as(); +} + +inline Orphan JsonCodec::decode( + JsonValue::Reader input, ListSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline Orphan JsonCodec::decode( + JsonValue::Reader input, StructSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline DynamicCapability::Client JsonCodec::decode( + JsonValue::Reader input, InterfaceSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} +inline DynamicEnum JsonCodec::decode(JsonValue::Reader input, EnumSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} + +// ----------------------------------------------------------------------------- + +class JsonCodec::HandlerBase { + // Internal helper; ignore. +public: + virtual void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const = 0; + virtual Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const; + virtual void decodeStructBase(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, ReaderFor input, + JsonValue::Builder output) const = 0; + virtual Orphan decode(const JsonCodec& codec, JsonValue::Reader input, + Orphanage orphanage) const = 0; + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input, orphanage); + } + friend class JsonCodec; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, ReaderFor input, + JsonValue::Builder output) const = 0; + virtual void decode(const JsonCodec& codec, JsonValue::Reader input, + BuilderFor output) const = 0; + virtual Orphan decode(const JsonCodec& codec, JsonValue::Reader input, + Orphanage orphanage) const { + // If subclass does not override, fall back to regular version. + auto result = orphanage.newOrphan(); + decode(codec, input, result.get()); + return result; + } + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input, orphanage); + } + void decodeStructBase(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const override final { + decode(codec, input, output.as()); + } + friend class JsonCodec; +}; + +template <> +class JsonCodec::Handler: private JsonCodec::HandlerBase { + // Almost identical to Style::STRUCT except that we pass the struct type to decode(). + +public: + virtual void encode(const JsonCodec& codec, DynamicStruct::Reader input, + JsonValue::Builder output) const = 0; + virtual void decode(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const = 0; + virtual Orphan decode(const JsonCodec& codec, JsonValue::Reader input, + StructSchema type, Orphanage orphanage) const { + // If subclass does not override, fall back to regular version. + auto result = orphanage.newOrphan(type); + decode(codec, input, result.get()); + return result; + } + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input, type.asStruct(), orphanage); + } + void decodeStructBase(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const override final { + decode(codec, input, output.as()); + } + friend class JsonCodec; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, T input, JsonValue::Builder output) const = 0; + virtual T decode(const JsonCodec& codec, JsonValue::Reader input) const = 0; + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input); + } + friend class JsonCodec; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, typename T::Client input, + JsonValue::Builder output) const = 0; + virtual typename T::Client decode(const JsonCodec& codec, JsonValue::Reader input) const = 0; + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return orphanage.newOrphanCopy(decode(codec, input)); + } + friend class JsonCodec; +}; + +template +inline void JsonCodec::addTypeHandler(Handler& handler) { + addTypeHandlerImpl(Type::from(), handler); +} +inline void JsonCodec::addTypeHandler(Type type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(EnumSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(StructSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(ListSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(InterfaceSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} + +template +inline void JsonCodec::addFieldHandler(StructSchema::Field field, Handler& handler) { + addFieldHandlerImpl(field, Type::from(), handler); +} + +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +// TODO(someday): Implement support for registering handlers that cover thinsg like "all structs" +// or "all lists". Currently you can only target a specific struct or list type. + +} // namespace capnp + +#endif // CAPNP_COMPAT_JSON_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/dynamic.h b/phonelibs/capnp-cpp/include/capnp/dynamic.h new file mode 100644 index 00000000000000..fcefcc3bf2fee9 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/dynamic.h @@ -0,0 +1,1643 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file defines classes that can be used to manipulate messages based on schemas that are not +// known until runtime. This is also useful for writing generic code that uses schemas to handle +// arbitrary types in a generic way. +// +// Each of the classes defined here has a to() template method which converts an instance back to a +// native type. This method will throw an exception if the requested type does not match the +// schema. To convert native types to dynamic, use DynamicFactory. +// +// As always, underlying data is validated lazily, so you have to actually traverse the whole +// message if you want to validate all content. + +#ifndef CAPNP_DYNAMIC_H_ +#define CAPNP_DYNAMIC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "schema.h" +#include "layout.h" +#include "message.h" +#include "any.h" +#include "capability.h" + +namespace capnp { + +class MessageReader; +class MessageBuilder; + +struct DynamicValue { + DynamicValue() = delete; + + enum Type { + UNKNOWN, + // Means that the value has unknown type and content because it comes from a newer version of + // the schema, or from a newer version of Cap'n Proto that has new features that this version + // doesn't understand. + + VOID, + BOOL, + INT, + UINT, + FLOAT, + TEXT, + DATA, + LIST, + ENUM, + STRUCT, + CAPABILITY, + ANY_POINTER + }; + + class Reader; + class Builder; + class Pipeline; +}; +class DynamicEnum; +struct DynamicStruct { + DynamicStruct() = delete; + class Reader; + class Builder; + class Pipeline; +}; +struct DynamicList { + DynamicList() = delete; + class Reader; + class Builder; +}; +struct DynamicCapability { + DynamicCapability() = delete; + class Client; + class Server; +}; +template <> class Orphan; + +template struct DynamicTypeFor_; +template <> struct DynamicTypeFor_ { typedef DynamicEnum Type; }; +template <> struct DynamicTypeFor_ { typedef DynamicStruct Type; }; +template <> struct DynamicTypeFor_ { typedef DynamicList Type; }; +template <> struct DynamicTypeFor_ { typedef DynamicCapability Type; }; + +template +using DynamicTypeFor = typename DynamicTypeFor_()>::Type; + +template +ReaderFor>> toDynamic(T&& value); +template +BuilderFor>> toDynamic(T&& value); +template +DynamicTypeFor> toDynamic(T&& value); +template +typename DynamicTypeFor>::Client toDynamic(kj::Own&& value); + +namespace _ { // private + +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; + +} // namespace _ (private) + +template <> inline constexpr Style style() { return Style::POINTER; } +template <> inline constexpr Style style() { return Style::PRIMITIVE; } +template <> inline constexpr Style style() { return Style::STRUCT; } +template <> inline constexpr Style style() { return Style::POINTER; } +template <> inline constexpr Style style() { return Style::CAPABILITY; } + +// ------------------------------------------------------------------- + +class DynamicEnum { +public: + DynamicEnum() = default; + inline DynamicEnum(EnumSchema::Enumerant enumerant) + : schema(enumerant.getContainingEnum()), value(enumerant.getOrdinal()) {} + inline DynamicEnum(EnumSchema schema, uint16_t value) + : schema(schema), value(value) {} + + template () == Kind::ENUM>> + inline DynamicEnum(T&& value): DynamicEnum(toDynamic(value)) {} + + template + inline T as() const { return static_cast(asImpl(typeId())); } + // Cast to a native enum type. + + inline EnumSchema getSchema() const { return schema; } + + kj::Maybe getEnumerant() const; + // Get which enumerant this enum value represents. Returns nullptr if the numeric value does not + // correspond to any enumerant in the schema -- this can happen if the data was built using a + // newer schema that has more values defined. + + inline uint16_t getRaw() const { return value; } + // Returns the raw underlying enum value. + +private: + EnumSchema schema; + uint16_t value; + + uint16_t asImpl(uint64_t requestedTypeId) const; + + friend struct DynamicStruct; + friend struct DynamicList; + friend struct DynamicValue; + template + friend DynamicTypeFor> toDynamic(T&& value); +}; + +// ------------------------------------------------------------------- + +class DynamicStruct::Reader { +public: + typedef DynamicStruct Reads; + + Reader() = default; + + template >() == Kind::STRUCT>> + inline Reader(T&& value): Reader(toDynamic(value)) {} + + inline MessageSize totalSize() const { return reader.totalSize().asPublic(); } + + template + typename T::Reader as() const; + // Convert the dynamic struct to its compiled-in type. + + inline StructSchema getSchema() const { return schema; } + + DynamicValue::Reader get(StructSchema::Field field) const; + // Read the given field value. + + bool has(StructSchema::Field field) const; + // Tests whether the given field is set to its default value. For pointer values, this does + // not actually traverse the value comparing it with the default, but simply returns true if the + // pointer is non-null. For members of unions, has() returns false if the union member is not + // active, but does not necessarily return true if the member is active (depends on the field's + // value). + + kj::Maybe which() const; + // If the struct contains an (unnamed) union, and the currently-active field within that union + // is known, this returns that field. Otherwise, it returns null. In other words, this returns + // null if there is no union present _or_ if the union's discriminant is set to an unrecognized + // value. This could happen in particular when receiving a message from a sender who has a + // newer version of the protocol and is using a field of the union that you don't know about yet. + + DynamicValue::Reader get(kj::StringPtr name) const; + bool has(kj::StringPtr name) const; + // Shortcuts to access fields by name. These throw exceptions if no such field exists. + +private: + StructSchema schema; + _::StructReader reader; + + inline Reader(StructSchema schema, _::StructReader reader) + : schema(schema), reader(reader) {} + Reader(StructSchema schema, const _::OrphanBuilder& orphan); + + bool isSetInUnion(StructSchema::Field field) const; + void verifySetInUnion(StructSchema::Field field) const; + static DynamicValue::Reader getImpl(_::StructReader reader, StructSchema::Field field); + + template + friend struct _::PointerHelpers; + friend class DynamicStruct::Builder; + friend struct DynamicList; + friend class MessageReader; + friend class MessageBuilder; + template + friend struct ::capnp::ToDynamic_; + friend kj::StringTree _::structString( + _::StructReader reader, const _::RawBrandedSchema& schema); + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +class DynamicStruct::Builder { +public: + typedef DynamicStruct Builds; + + Builder() = default; + inline Builder(decltype(nullptr)) {} + + template >() == Kind::STRUCT>> + inline Builder(T&& value): Builder(toDynamic(value)) {} + + inline MessageSize totalSize() const { return asReader().totalSize(); } + + template + typename T::Builder as(); + // Cast to a particular struct type. + + inline StructSchema getSchema() const { return schema; } + + DynamicValue::Builder get(StructSchema::Field field); + // Read the given field value. + + inline bool has(StructSchema::Field field) { return asReader().has(field); } + // Tests whether the given field is set to its default value. For pointer values, this does + // not actually traverse the value comparing it with the default, but simply returns true if the + // pointer is non-null. For members of unions, has() returns whether the field is currently + // active and the union as a whole is non-default -- so, the only time has() will return false + // for an active union field is if it is the default active field and it has its default value. + + kj::Maybe which(); + // If the struct contains an (unnamed) union, and the currently-active field within that union + // is known, this returns that field. Otherwise, it returns null. In other words, this returns + // null if there is no union present _or_ if the union's discriminant is set to an unrecognized + // value. This could happen in particular when receiving a message from a sender who has a + // newer version of the protocol and is using a field of the union that you don't know about yet. + + void set(StructSchema::Field field, const DynamicValue::Reader& value); + // Set the given field value. + + DynamicValue::Builder init(StructSchema::Field field); + DynamicValue::Builder init(StructSchema::Field field, uint size); + // Init a struct, list, or blob field. + + void adopt(StructSchema::Field field, Orphan&& orphan); + Orphan disown(StructSchema::Field field); + // Adopt/disown. This works even for non-pointer fields: adopt() becomes equivalent to set() + // and disown() becomes like get() followed by clear(). + + void clear(StructSchema::Field field); + // Clear a field, setting it to its default value. For pointer fields, this actually makes the + // field null. + + DynamicValue::Builder get(kj::StringPtr name); + bool has(kj::StringPtr name); + void set(kj::StringPtr name, const DynamicValue::Reader& value); + void set(kj::StringPtr name, std::initializer_list value); + DynamicValue::Builder init(kj::StringPtr name); + DynamicValue::Builder init(kj::StringPtr name, uint size); + void adopt(kj::StringPtr name, Orphan&& orphan); + Orphan disown(kj::StringPtr name); + void clear(kj::StringPtr name); + // Shortcuts to access fields by name. These throw exceptions if no such field exists. + + Reader asReader() const; + +private: + StructSchema schema; + _::StructBuilder builder; + + inline Builder(StructSchema schema, _::StructBuilder builder) + : schema(schema), builder(builder) {} + Builder(StructSchema schema, _::OrphanBuilder& orphan); + + bool isSetInUnion(StructSchema::Field field); + void verifySetInUnion(StructSchema::Field field); + void setInUnion(StructSchema::Field field); + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class MessageReader; + friend class MessageBuilder; + template + friend struct ::capnp::ToDynamic_; + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +class DynamicStruct::Pipeline { +public: + typedef DynamicStruct Pipelines; + + inline Pipeline(decltype(nullptr)): typeless(nullptr) {} + + template + typename T::Pipeline releaseAs(); + // Convert the dynamic pipeline to its compiled-in type. + + inline StructSchema getSchema() { return schema; } + + DynamicValue::Pipeline get(StructSchema::Field field); + // Read the given field value. + + DynamicValue::Pipeline get(kj::StringPtr name); + // Get by string name. + +private: + StructSchema schema; + AnyPointer::Pipeline typeless; + + inline explicit Pipeline(StructSchema schema, AnyPointer::Pipeline&& typeless) + : schema(schema), typeless(kj::mv(typeless)) {} + + friend class Request; +}; + +// ------------------------------------------------------------------- + +class DynamicList::Reader { +public: + typedef DynamicList Reads; + + inline Reader(): reader(ElementSize::VOID) {} + + template >() == Kind::LIST>> + inline Reader(T&& value): Reader(toDynamic(value)) {} + + template + typename T::Reader as() const; + // Try to convert to any List, Data, or Text. Throws an exception if the underlying data + // can't possibly represent the requested type. + + inline ListSchema getSchema() const { return schema; } + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + DynamicValue::Reader operator[](uint index) const; + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + ListSchema schema; + _::ListReader reader; + + Reader(ListSchema schema, _::ListReader reader): schema(schema), reader(reader) {} + Reader(ListSchema schema, const _::OrphanBuilder& orphan); + + template + friend struct _::PointerHelpers; + friend struct DynamicStruct; + friend class DynamicList::Builder; + template + friend struct ::capnp::ToDynamic_; + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +class DynamicList::Builder { +public: + typedef DynamicList Builds; + + inline Builder(): builder(ElementSize::VOID) {} + inline Builder(decltype(nullptr)): builder(ElementSize::VOID) {} + + template >() == Kind::LIST>> + inline Builder(T&& value): Builder(toDynamic(value)) {} + + template + typename T::Builder as(); + // Try to convert to any List, Data, or Text. Throws an exception if the underlying data + // can't possibly represent the requested type. + + inline ListSchema getSchema() const { return schema; } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + DynamicValue::Builder operator[](uint index); + void set(uint index, const DynamicValue::Reader& value); + DynamicValue::Builder init(uint index, uint size); + void adopt(uint index, Orphan&& orphan); + Orphan disown(uint index); + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + void copyFrom(std::initializer_list value); + + Reader asReader() const; + +private: + ListSchema schema; + _::ListBuilder builder; + + Builder(ListSchema schema, _::ListBuilder builder): schema(schema), builder(builder) {} + Builder(ListSchema schema, _::OrphanBuilder& orphan); + + template + friend struct _::PointerHelpers; + friend struct DynamicStruct; + template + friend struct ::capnp::ToDynamic_; + friend class Orphanage; + template + friend struct _::OrphanGetImpl; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +// ------------------------------------------------------------------- + +class DynamicCapability::Client: public Capability::Client { +public: + typedef DynamicCapability Calls; + typedef DynamicCapability Reads; + + Client() = default; + + template >() == Kind::INTERFACE>> + inline Client(T&& client); + + template ()>> + inline Client(kj::Own&& server); + + template () == Kind::INTERFACE>> + typename T::Client as(); + template () == Kind::INTERFACE>> + typename T::Client releaseAs(); + // Convert to any client type. + + Client upcast(InterfaceSchema requestedSchema); + // Upcast to a superclass. Throws an exception if `schema` is not a superclass. + + inline InterfaceSchema getSchema() { return schema; } + + Request newRequest( + InterfaceSchema::Method method, kj::Maybe sizeHint = nullptr); + Request newRequest( + kj::StringPtr methodName, kj::Maybe sizeHint = nullptr); + +private: + InterfaceSchema schema; + + Client(InterfaceSchema schema, kj::Own&& hook) + : Capability::Client(kj::mv(hook)), schema(schema) {} + + template + inline Client(InterfaceSchema schema, kj::Own&& server); + + friend struct Capability; + friend struct DynamicStruct; + friend struct DynamicList; + friend struct DynamicValue; + friend class Orphan; + friend class Orphan; + friend class Orphan; + template + friend struct _::PointerHelpers; +}; + +class DynamicCapability::Server: public Capability::Server { +public: + typedef DynamicCapability Serves; + + Server(InterfaceSchema schema): schema(schema) {} + + virtual kj::Promise call(InterfaceSchema::Method method, + CallContext context) = 0; + + kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + CallContext context) override final; + + inline InterfaceSchema getSchema() const { return schema; } + +private: + InterfaceSchema schema; +}; + +template <> +class Request: public DynamicStruct::Builder { + // Specialization of `Request` for DynamicStruct. + +public: + inline Request(DynamicStruct::Builder builder, kj::Own&& hook, + StructSchema resultSchema) + : DynamicStruct::Builder(builder), hook(kj::mv(hook)), resultSchema(resultSchema) {} + + RemotePromise send(); + // Send the call and return a promise for the results. + +private: + kj::Own hook; + StructSchema resultSchema; + + friend class Capability::Client; + friend struct DynamicCapability; + template + friend class CallContext; + friend class RequestHook; +}; + +template <> +class CallContext: public kj::DisallowConstCopy { + // Wrapper around CallContextHook with a specific return type. + // + // Methods of this class may only be called from within the server's event loop, not from other + // threads. + +public: + explicit CallContext(CallContextHook& hook, StructSchema paramType, StructSchema resultType); + + DynamicStruct::Reader getParams(); + void releaseParams(); + DynamicStruct::Builder getResults(kj::Maybe sizeHint = nullptr); + DynamicStruct::Builder initResults(kj::Maybe sizeHint = nullptr); + void setResults(DynamicStruct::Reader value); + void adoptResults(Orphan&& value); + Orphanage getResultsOrphanage(kj::Maybe sizeHint = nullptr); + template + kj::Promise tailCall(Request&& tailRequest); + void allowCancellation(); + +private: + CallContextHook* hook; + StructSchema paramType; + StructSchema resultType; + + friend class DynamicCapability::Server; +}; + +// ------------------------------------------------------------------- + +// Make sure ReaderFor and BuilderFor work for DynamicEnum, DynamicStruct, and +// DynamicList, so that we can define DynamicValue::as(). + +template <> struct ReaderFor_ { typedef DynamicEnum Type; }; +template <> struct BuilderFor_ { typedef DynamicEnum Type; }; +template <> struct ReaderFor_ { typedef DynamicStruct::Reader Type; }; +template <> struct BuilderFor_ { typedef DynamicStruct::Builder Type; }; +template <> struct ReaderFor_ { typedef DynamicList::Reader Type; }; +template <> struct BuilderFor_ { typedef DynamicList::Builder Type; }; +template <> struct ReaderFor_ { typedef DynamicCapability::Client Type; }; +template <> struct BuilderFor_ { typedef DynamicCapability::Client Type; }; +template <> struct PipelineFor_ { typedef DynamicCapability::Client Type; }; + +class DynamicValue::Reader { +public: + typedef DynamicValue Reads; + + inline Reader(decltype(nullptr) n = nullptr); // UNKNOWN + inline Reader(Void value); + inline Reader(bool value); + inline Reader(char value); + inline Reader(signed char value); + inline Reader(short value); + inline Reader(int value); + inline Reader(long value); + inline Reader(long long value); + inline Reader(unsigned char value); + inline Reader(unsigned short value); + inline Reader(unsigned int value); + inline Reader(unsigned long value); + inline Reader(unsigned long long value); + inline Reader(float value); + inline Reader(double value); + inline Reader(const char* value); // Text + inline Reader(const Text::Reader& value); + inline Reader(const Data::Reader& value); + inline Reader(const DynamicList::Reader& value); + inline Reader(DynamicEnum value); + inline Reader(const DynamicStruct::Reader& value); + inline Reader(const AnyPointer::Reader& value); + inline Reader(DynamicCapability::Client& value); + inline Reader(DynamicCapability::Client&& value); + template ()>> + inline Reader(kj::Own&& value); + Reader(ConstSchema constant); + + template ()))> + inline Reader(T&& value): Reader(toDynamic(kj::mv(value))) {} + + Reader(const Reader& other); + Reader(Reader&& other) noexcept; + ~Reader() noexcept(false); + Reader& operator=(const Reader& other); + Reader& operator=(Reader&& other); + // Unfortunately, we cannot use the implicit definitions of these since DynamicCapability is not + // trivially copyable. + + template + inline ReaderFor as() const { return AsImpl::apply(*this); } + // Use to interpret the value as some Cap'n Proto type. Allowed types are: + // - Void, bool, [u]int{8,16,32,64}_t, float, double, any enum: Returns the raw value. + // - Text, Data, AnyPointer, any struct type: Returns the corresponding Reader. + // - List for any T listed above: Returns List::Reader. + // - DynamicEnum: Returns the corresponding type. + // - DynamicStruct, DynamicList: Returns the corresponding Reader. + // - Any capability type, including DynamicCapability: Returns the corresponding Client. + // - DynamicValue: Returns an identical Reader. Useful to avoid special-casing in generic code. + // (TODO(perf): On GCC 4.8 / Clang 3.3, provide rvalue-qualified version that avoids + // refcounting.) + // + // DynamicValue allows various implicit conversions, mostly just to make the interface friendlier. + // - Any integer can be converted to any other integer type so long as the actual value is within + // the new type's range. + // - Floating-point types can be converted to integers as long as no information would be lost + // in the conversion. + // - Integers can be converted to floating points. This may lose information, but won't throw. + // - Float32/Float64 can be converted between each other. Converting Float64 -> Float32 may lose + // information, but won't throw. + // - Text can be converted to an enum, if the Text matches one of the enumerant names (but not + // vice-versa). + // - Capabilities can be upcast (cast to a supertype), but not downcast. + // + // Any other conversion attempt will throw an exception. + + inline Type getType() const { return type; } + // Get the type of this value. + +private: + Type type; + + union { + Void voidValue; + bool boolValue; + int64_t intValue; + uint64_t uintValue; + double floatValue; + Text::Reader textValue; + Data::Reader dataValue; + DynamicList::Reader listValue; + DynamicEnum enumValue; + DynamicStruct::Reader structValue; + AnyPointer::Reader anyPointerValue; + + mutable DynamicCapability::Client capabilityValue; + // Declared mutable because `Client`s normally cannot be const. + + // Warning: Copy/move constructors assume all these types are trivially copyable except + // Capability. + }; + + template ()> struct AsImpl; + // Implementation backing the as() method. Needs to be a struct to allow partial + // specialization. Has a method apply() which does the work. + + friend class Orphanage; // to speed up newOrphanCopy(DynamicValue::Reader) +}; + +class DynamicValue::Builder { +public: + typedef DynamicValue Builds; + + inline Builder(decltype(nullptr) n = nullptr); // UNKNOWN + inline Builder(Void value); + inline Builder(bool value); + inline Builder(char value); + inline Builder(signed char value); + inline Builder(short value); + inline Builder(int value); + inline Builder(long value); + inline Builder(long long value); + inline Builder(unsigned char value); + inline Builder(unsigned short value); + inline Builder(unsigned int value); + inline Builder(unsigned long value); + inline Builder(unsigned long long value); + inline Builder(float value); + inline Builder(double value); + inline Builder(Text::Builder value); + inline Builder(Data::Builder value); + inline Builder(DynamicList::Builder value); + inline Builder(DynamicEnum value); + inline Builder(DynamicStruct::Builder value); + inline Builder(AnyPointer::Builder value); + inline Builder(DynamicCapability::Client& value); + inline Builder(DynamicCapability::Client&& value); + + template ()))> + inline Builder(T value): Builder(toDynamic(value)) {} + + Builder(Builder& other); + Builder(Builder&& other) noexcept; + ~Builder() noexcept(false); + Builder& operator=(Builder& other); + Builder& operator=(Builder&& other); + // Unfortunately, we cannot use the implicit definitions of these since DynamicCapability is not + // trivially copyable. + + template + inline BuilderFor as() { return AsImpl::apply(*this); } + // See DynamicValue::Reader::as(). + + inline Type getType() { return type; } + // Get the type of this value. + + Reader asReader() const; + +private: + Type type; + + union { + Void voidValue; + bool boolValue; + int64_t intValue; + uint64_t uintValue; + double floatValue; + Text::Builder textValue; + Data::Builder dataValue; + DynamicList::Builder listValue; + DynamicEnum enumValue; + DynamicStruct::Builder structValue; + AnyPointer::Builder anyPointerValue; + + mutable DynamicCapability::Client capabilityValue; + // Declared mutable because `Client`s normally cannot be const. + }; + + template ()> struct AsImpl; + // Implementation backing the as() method. Needs to be a struct to allow partial + // specialization. Has a method apply() which does the work. + + friend class Orphan; +}; + +class DynamicValue::Pipeline { +public: + typedef DynamicValue Pipelines; + + inline Pipeline(decltype(nullptr) n = nullptr); + inline Pipeline(DynamicStruct::Pipeline&& value); + inline Pipeline(DynamicCapability::Client&& value); + + Pipeline(Pipeline&& other) noexcept; + Pipeline& operator=(Pipeline&& other); + ~Pipeline() noexcept(false); + + template + inline PipelineFor releaseAs() { return AsImpl::apply(*this); } + + inline Type getType() { return type; } + // Get the type of this value. + +private: + Type type; + union { + DynamicStruct::Pipeline structValue; + DynamicCapability::Client capabilityValue; + }; + + template ()> struct AsImpl; + // Implementation backing the releaseAs() method. Needs to be a struct to allow partial + // specialization. Has a method apply() which does the work. +}; + +kj::StringTree KJ_STRINGIFY(const DynamicValue::Reader& value); +kj::StringTree KJ_STRINGIFY(const DynamicValue::Builder& value); +kj::StringTree KJ_STRINGIFY(DynamicEnum value); +kj::StringTree KJ_STRINGIFY(const DynamicStruct::Reader& value); +kj::StringTree KJ_STRINGIFY(const DynamicStruct::Builder& value); +kj::StringTree KJ_STRINGIFY(const DynamicList::Reader& value); +kj::StringTree KJ_STRINGIFY(const DynamicList::Builder& value); + +// ------------------------------------------------------------------- +// Orphan <-> Dynamic glue + +template <> +class Orphan { +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + + template () == Kind::STRUCT>> + inline Orphan(Orphan&& other): schema(Schema::from()), builder(kj::mv(other.builder)) {} + + DynamicStruct::Builder get(); + DynamicStruct::Reader getReader() const; + + template + Orphan releaseAs(); + // Like DynamicStruct::Builder::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + StructSchema schema; + _::OrphanBuilder builder; + + inline Orphan(StructSchema schema, _::OrphanBuilder&& builder) + : schema(schema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class MessageBuilder; +}; + +template <> +class Orphan { +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + + template () == Kind::LIST>> + inline Orphan(Orphan&& other): schema(Schema::from()), builder(kj::mv(other.builder)) {} + + DynamicList::Builder get(); + DynamicList::Reader getReader() const; + + template + Orphan releaseAs(); + // Like DynamicList::Builder::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + + // TODO(someday): Support truncate(). + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + ListSchema schema; + _::OrphanBuilder builder; + + inline Orphan(ListSchema schema, _::OrphanBuilder&& builder) + : schema(schema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class Orphanage; + friend class Orphan; + friend class Orphan; +}; + +template <> +class Orphan { +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + + template () == Kind::INTERFACE>> + inline Orphan(Orphan&& other): schema(Schema::from()), builder(kj::mv(other.builder)) {} + + DynamicCapability::Client get(); + DynamicCapability::Client getReader() const; + + template + Orphan releaseAs(); + // Like DynamicCapability::Client::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + InterfaceSchema schema; + _::OrphanBuilder builder; + + inline Orphan(InterfaceSchema schema, _::OrphanBuilder&& builder) + : schema(schema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class Orphanage; + friend class Orphan; + friend class Orphan; +}; + +template <> +class Orphan { +public: + inline Orphan(decltype(nullptr) n = nullptr): type(DynamicValue::UNKNOWN) {} + inline Orphan(Void value); + inline Orphan(bool value); + inline Orphan(char value); + inline Orphan(signed char value); + inline Orphan(short value); + inline Orphan(int value); + inline Orphan(long value); + inline Orphan(long long value); + inline Orphan(unsigned char value); + inline Orphan(unsigned short value); + inline Orphan(unsigned int value); + inline Orphan(unsigned long value); + inline Orphan(unsigned long long value); + inline Orphan(float value); + inline Orphan(double value); + inline Orphan(DynamicEnum value); + Orphan(Orphan&&) = default; + template + Orphan(Orphan&&); + Orphan(Orphan&&); + Orphan(void*) = delete; // So Orphan(bool) doesn't accept pointers. + KJ_DISALLOW_COPY(Orphan); + + Orphan& operator=(Orphan&&) = default; + + inline DynamicValue::Type getType() { return type; } + + DynamicValue::Builder get(); + DynamicValue::Reader getReader() const; + + template + Orphan releaseAs(); + // Like DynamicValue::Builder::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + +private: + DynamicValue::Type type; + union { + Void voidValue; + bool boolValue; + int64_t intValue; + uint64_t uintValue; + double floatValue; + DynamicEnum enumValue; + StructSchema structSchema; + ListSchema listSchema; + InterfaceSchema interfaceSchema; + }; + + _::OrphanBuilder builder; + // Only used if `type` is a pointer type. + + Orphan(DynamicValue::Builder value, _::OrphanBuilder&& builder); + Orphan(DynamicValue::Type type, _::OrphanBuilder&& builder) + : type(type), builder(kj::mv(builder)) {} + Orphan(StructSchema structSchema, _::OrphanBuilder&& builder) + : type(DynamicValue::STRUCT), structSchema(structSchema), builder(kj::mv(builder)) {} + Orphan(ListSchema listSchema, _::OrphanBuilder&& builder) + : type(DynamicValue::LIST), listSchema(listSchema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicStruct; + friend struct DynamicList; + friend struct AnyPointer; + friend class Orphanage; +}; + +template +inline Orphan::Orphan(Orphan&& other) + : Orphan(other.get(), kj::mv(other.builder)) {} + +inline Orphan::Orphan(Orphan&& other) + : type(DynamicValue::ANY_POINTER), builder(kj::mv(other.builder)) {} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + return Orphan(kj::mv(builder)); +} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + return Orphan(kj::mv(builder)); +} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + return Orphan(kj::mv(builder)); +} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + type = DynamicValue::UNKNOWN; + return Orphan(kj::mv(builder)); +} + +template <> +Orphan Orphan::releaseAs(); +template <> +Orphan Orphan::releaseAs(); +template <> +Orphan Orphan::releaseAs(); +template <> +Orphan Orphan::releaseAs(); + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::StructBuilder apply(DynamicStruct::Builder& t) { + return t.builder; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::ListBuilder apply(DynamicList::Builder& t) { + return t.builder; + } +}; + +template <> +inline Orphan Orphanage::newOrphanCopy( + DynamicStruct::Reader copyFrom) const { + return Orphan( + copyFrom.getSchema(), _::OrphanBuilder::copy(arena, capTable, copyFrom.reader)); +} + +template <> +inline Orphan Orphanage::newOrphanCopy( + DynamicList::Reader copyFrom) const { + return Orphan(copyFrom.getSchema(), + _::OrphanBuilder::copy(arena, capTable, copyFrom.reader)); +} + +template <> +inline Orphan Orphanage::newOrphanCopy( + DynamicCapability::Client copyFrom) const { + return Orphan( + copyFrom.getSchema(), _::OrphanBuilder::copy(arena, capTable, copyFrom.hook->addRef())); +} + +template <> +Orphan Orphanage::newOrphanCopy( + DynamicValue::Reader copyFrom) const; + +namespace _ { // private + +template <> +struct PointerHelpers { + // getDynamic() is used when an AnyPointer's get() accessor is passed arguments, because for + // non-dynamic types PointerHelpers::get() takes a default value as the third argument, and we + // don't want people to accidentally be able to provide their own default value. + static DynamicStruct::Reader getDynamic(PointerReader reader, StructSchema schema); + static DynamicStruct::Builder getDynamic(PointerBuilder builder, StructSchema schema); + static void set(PointerBuilder builder, const DynamicStruct::Reader& value); + static DynamicStruct::Builder init(PointerBuilder builder, StructSchema schema); + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder, StructSchema schema) { + return Orphan(schema, builder.disown()); + } +}; + +template <> +struct PointerHelpers { + // getDynamic() is used when an AnyPointer's get() accessor is passed arguments, because for + // non-dynamic types PointerHelpers::get() takes a default value as the third argument, and we + // don't want people to accidentally be able to provide their own default value. + static DynamicList::Reader getDynamic(PointerReader reader, ListSchema schema); + static DynamicList::Builder getDynamic(PointerBuilder builder, ListSchema schema); + static void set(PointerBuilder builder, const DynamicList::Reader& value); + static DynamicList::Builder init(PointerBuilder builder, ListSchema schema, uint size); + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder, ListSchema schema) { + return Orphan(schema, builder.disown()); + } +}; + +template <> +struct PointerHelpers { + // getDynamic() is used when an AnyPointer's get() accessor is passed arguments, because for + // non-dynamic types PointerHelpers::get() takes a default value as the third argument, and we + // don't want people to accidentally be able to provide their own default value. + static DynamicCapability::Client getDynamic(PointerReader reader, InterfaceSchema schema); + static DynamicCapability::Client getDynamic(PointerBuilder builder, InterfaceSchema schema); + static void set(PointerBuilder builder, DynamicCapability::Client& value); + static void set(PointerBuilder builder, DynamicCapability::Client&& value); + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder, InterfaceSchema schema) { + return Orphan(schema, builder.disown()); + } +}; + +} // namespace _ (private) + +template +inline ReaderFor AnyPointer::Reader::getAs(StructSchema schema) const { + return _::PointerHelpers::getDynamic(reader, schema); +} +template +inline ReaderFor AnyPointer::Reader::getAs(ListSchema schema) const { + return _::PointerHelpers::getDynamic(reader, schema); +} +template +inline ReaderFor AnyPointer::Reader::getAs(InterfaceSchema schema) const { + return _::PointerHelpers::getDynamic(reader, schema); +} +template +inline BuilderFor AnyPointer::Builder::getAs(StructSchema schema) { + return _::PointerHelpers::getDynamic(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::getAs(ListSchema schema) { + return _::PointerHelpers::getDynamic(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::getAs(InterfaceSchema schema) { + return _::PointerHelpers::getDynamic(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::initAs(StructSchema schema) { + return _::PointerHelpers::init(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::initAs(ListSchema schema, uint elementCount) { + return _::PointerHelpers::init(builder, schema, elementCount); +} +template <> +inline void AnyPointer::Builder::setAs(DynamicStruct::Reader value) { + return _::PointerHelpers::set(builder, value); +} +template <> +inline void AnyPointer::Builder::setAs(DynamicList::Reader value) { + return _::PointerHelpers::set(builder, value); +} +template <> +inline void AnyPointer::Builder::setAs(DynamicCapability::Client value) { + return _::PointerHelpers::set(builder, kj::mv(value)); +} +template <> +void AnyPointer::Builder::adopt(Orphan&& orphan); +template +inline Orphan AnyPointer::Builder::disownAs(StructSchema schema) { + return _::PointerHelpers::disown(builder, schema); +} +template +inline Orphan AnyPointer::Builder::disownAs(ListSchema schema) { + return _::PointerHelpers::disown(builder, schema); +} +template +inline Orphan AnyPointer::Builder::disownAs(InterfaceSchema schema) { + return _::PointerHelpers::disown(builder, schema); +} + +// We have to declare the methods below inline because Clang and GCC disagree about how to mangle +// their symbol names. +template <> +inline DynamicStruct::Builder Orphan::getAs(StructSchema schema) { + return DynamicStruct::Builder(schema, builder); +} +template <> +inline DynamicStruct::Reader Orphan::getAsReader( + StructSchema schema) const { + return DynamicStruct::Reader(schema, builder); +} +template <> +inline Orphan Orphan::releaseAs(StructSchema schema) { + return Orphan(schema, kj::mv(builder)); +} +template <> +inline DynamicList::Builder Orphan::getAs(ListSchema schema) { + return DynamicList::Builder(schema, builder); +} +template <> +inline DynamicList::Reader Orphan::getAsReader(ListSchema schema) const { + return DynamicList::Reader(schema, builder); +} +template <> +inline Orphan Orphan::releaseAs(ListSchema schema) { + return Orphan(schema, kj::mv(builder)); +} +template <> +inline DynamicCapability::Client Orphan::getAs( + InterfaceSchema schema) { + return DynamicCapability::Client(schema, builder.asCapability()); +} +template <> +inline DynamicCapability::Client Orphan::getAsReader( + InterfaceSchema schema) const { + return DynamicCapability::Client(schema, builder.asCapability()); +} +template <> +inline Orphan Orphan::releaseAs( + InterfaceSchema schema) { + return Orphan(schema, kj::mv(builder)); +} + +// ======================================================================================= +// Inline implementation details. + +template +struct ToDynamic_ { + static inline DynamicStruct::Reader apply(const typename T::Reader& value) { + return DynamicStruct::Reader(Schema::from(), value._reader); + } + static inline DynamicStruct::Builder apply(typename T::Builder& value) { + return DynamicStruct::Builder(Schema::from(), value._builder); + } +}; + +template +struct ToDynamic_ { + static inline DynamicList::Reader apply(const typename T::Reader& value) { + return DynamicList::Reader(Schema::from(), value.reader); + } + static inline DynamicList::Builder apply(typename T::Builder& value) { + return DynamicList::Builder(Schema::from(), value.builder); + } +}; + +template +struct ToDynamic_ { + static inline DynamicCapability::Client apply(typename T::Client value) { + return DynamicCapability::Client(kj::mv(value)); + } + static inline DynamicCapability::Client apply(typename T::Client&& value) { + return DynamicCapability::Client(kj::mv(value)); + } +}; + +template +ReaderFor>> toDynamic(T&& value) { + return ToDynamic_>::apply(value); +} +template +BuilderFor>> toDynamic(T&& value) { + return ToDynamic_>::apply(value); +} +template +DynamicTypeFor> toDynamic(T&& value) { + return DynamicEnum(Schema::from>(), static_cast(value)); +} +template +typename DynamicTypeFor>::Client toDynamic(kj::Own&& value) { + return typename FromServer::Client(kj::mv(value)); +} + +inline DynamicValue::Reader::Reader(std::nullptr_t n): type(UNKNOWN) {} +inline DynamicValue::Builder::Builder(std::nullptr_t n): type(UNKNOWN) {} + +#define CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(cppType, typeTag, fieldName) \ +inline DynamicValue::Reader::Reader(cppType value) \ + : type(typeTag), fieldName##Value(value) {} \ +inline DynamicValue::Builder::Builder(cppType value) \ + : type(typeTag), fieldName##Value(value) {} \ +inline Orphan::Orphan(cppType value) \ + : type(DynamicValue::typeTag), fieldName##Value(value) {} + +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(Void, VOID, void); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(bool, BOOL, bool); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(char, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(signed char, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(short, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(int, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(long, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(long long, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned char, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned short, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned int, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned long, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned long long, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(float, FLOAT, float); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(double, FLOAT, float); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(DynamicEnum, ENUM, enum); +#undef CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR + +#define CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(cppType, typeTag, fieldName) \ +inline DynamicValue::Reader::Reader(const cppType::Reader& value) \ + : type(typeTag), fieldName##Value(value) {} \ +inline DynamicValue::Builder::Builder(cppType::Builder value) \ + : type(typeTag), fieldName##Value(value) {} + +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(Text, TEXT, text); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(Data, DATA, data); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(DynamicList, LIST, list); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(DynamicStruct, STRUCT, struct); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(AnyPointer, ANY_POINTER, anyPointer); + +#undef CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR + +inline DynamicValue::Reader::Reader(DynamicCapability::Client& value) + : type(CAPABILITY), capabilityValue(value) {} +inline DynamicValue::Reader::Reader(DynamicCapability::Client&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} +template +inline DynamicValue::Reader::Reader(kj::Own&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} +inline DynamicValue::Builder::Builder(DynamicCapability::Client& value) + : type(CAPABILITY), capabilityValue(value) {} +inline DynamicValue::Builder::Builder(DynamicCapability::Client&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} + +inline DynamicValue::Reader::Reader(const char* value): Reader(Text::Reader(value)) {} + +#define CAPNP_DECLARE_TYPE(discrim, typeName) \ +template <> \ +struct DynamicValue::Reader::AsImpl { \ + static ReaderFor apply(const Reader& reader); \ +}; \ +template <> \ +struct DynamicValue::Builder::AsImpl { \ + static BuilderFor apply(Builder& builder); \ +}; + +//CAPNP_DECLARE_TYPE(VOID, Void) +CAPNP_DECLARE_TYPE(BOOL, bool) +CAPNP_DECLARE_TYPE(INT8, int8_t) +CAPNP_DECLARE_TYPE(INT16, int16_t) +CAPNP_DECLARE_TYPE(INT32, int32_t) +CAPNP_DECLARE_TYPE(INT64, int64_t) +CAPNP_DECLARE_TYPE(UINT8, uint8_t) +CAPNP_DECLARE_TYPE(UINT16, uint16_t) +CAPNP_DECLARE_TYPE(UINT32, uint32_t) +CAPNP_DECLARE_TYPE(UINT64, uint64_t) +CAPNP_DECLARE_TYPE(FLOAT32, float) +CAPNP_DECLARE_TYPE(FLOAT64, double) + +CAPNP_DECLARE_TYPE(TEXT, Text) +CAPNP_DECLARE_TYPE(DATA, Data) +CAPNP_DECLARE_TYPE(LIST, DynamicList) +CAPNP_DECLARE_TYPE(STRUCT, DynamicStruct) +CAPNP_DECLARE_TYPE(INTERFACE, DynamicCapability) +CAPNP_DECLARE_TYPE(ENUM, DynamicEnum) +CAPNP_DECLARE_TYPE(ANY_POINTER, AnyPointer) +#undef CAPNP_DECLARE_TYPE + +// CAPNP_DECLARE_TYPE(Void) causes gcc 4.7 to segfault. If I do it manually and remove the +// ReaderFor<> and BuilderFor<> wrappers, it works. +template <> +struct DynamicValue::Reader::AsImpl { + static Void apply(const Reader& reader); +}; +template <> +struct DynamicValue::Builder::AsImpl { + static Void apply(Builder& builder); +}; + +template +struct DynamicValue::Reader::AsImpl { + static T apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static T apply(Builder& builder) { + return builder.as().as(); + } +}; + +template +struct DynamicValue::Reader::AsImpl { + static typename T::Reader apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static typename T::Builder apply(Builder& builder) { + return builder.as().as(); + } +}; + +template +struct DynamicValue::Reader::AsImpl { + static typename T::Reader apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static typename T::Builder apply(Builder& builder) { + return builder.as().as(); + } +}; + +template +struct DynamicValue::Reader::AsImpl { + static typename T::Client apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static typename T::Client apply(Builder& builder) { + return builder.as().as(); + } +}; + +template <> +struct DynamicValue::Reader::AsImpl { + static DynamicValue::Reader apply(const Reader& reader) { + return reader; + } +}; +template <> +struct DynamicValue::Builder::AsImpl { + static DynamicValue::Builder apply(Builder& builder) { + return builder; + } +}; + +inline DynamicValue::Pipeline::Pipeline(std::nullptr_t n): type(UNKNOWN) {} +inline DynamicValue::Pipeline::Pipeline(DynamicStruct::Pipeline&& value) + : type(STRUCT), structValue(kj::mv(value)) {} +inline DynamicValue::Pipeline::Pipeline(DynamicCapability::Client&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} + +template +struct DynamicValue::Pipeline::AsImpl { + static typename T::Pipeline apply(Pipeline& pipeline) { + return pipeline.releaseAs().releaseAs(); + } +}; +template +struct DynamicValue::Pipeline::AsImpl { + static typename T::Client apply(Pipeline& pipeline) { + return pipeline.releaseAs().releaseAs(); + } +}; +template <> +struct DynamicValue::Pipeline::AsImpl { + static PipelineFor apply(Pipeline& pipeline); +}; +template <> +struct DynamicValue::Pipeline::AsImpl { + static PipelineFor apply(Pipeline& pipeline); +}; + +// ------------------------------------------------------------------- + +template +typename T::Reader DynamicStruct::Reader::as() const { + static_assert(kind() == Kind::STRUCT, + "DynamicStruct::Reader::as() can only convert to struct types."); + schema.requireUsableAs(); + return typename T::Reader(reader); +} + +template +typename T::Builder DynamicStruct::Builder::as() { + static_assert(kind() == Kind::STRUCT, + "DynamicStruct::Builder::as() can only convert to struct types."); + schema.requireUsableAs(); + return typename T::Builder(builder); +} + +template <> +inline DynamicStruct::Reader DynamicStruct::Reader::as() const { + return *this; +} +template <> +inline DynamicStruct::Builder DynamicStruct::Builder::as() { + return *this; +} + +inline DynamicStruct::Reader DynamicStruct::Builder::asReader() const { + return DynamicStruct::Reader(schema, builder.asReader()); +} + +template <> +inline AnyStruct::Reader DynamicStruct::Reader::as() const { + return AnyStruct::Reader(reader); +} + +template <> +inline AnyStruct::Builder DynamicStruct::Builder::as() { + return AnyStruct::Builder(builder); +} + +template +typename T::Pipeline DynamicStruct::Pipeline::releaseAs() { + static_assert(kind() == Kind::STRUCT, + "DynamicStruct::Pipeline::releaseAs() can only convert to struct types."); + schema.requireUsableAs(); + return typename T::Pipeline(kj::mv(typeless)); +} + +// ------------------------------------------------------------------- + +template +typename T::Reader DynamicList::Reader::as() const { + static_assert(kind() == Kind::LIST, + "DynamicStruct::Reader::as() can only convert to list types."); + schema.requireUsableAs(); + return typename T::Reader(reader); +} +template +typename T::Builder DynamicList::Builder::as() { + static_assert(kind() == Kind::LIST, + "DynamicStruct::Builder::as() can only convert to list types."); + schema.requireUsableAs(); + return typename T::Builder(builder); +} + +template <> +inline DynamicList::Reader DynamicList::Reader::as() const { + return *this; +} +template <> +inline DynamicList::Builder DynamicList::Builder::as() { + return *this; +} + +template <> +inline AnyList::Reader DynamicList::Reader::as() const { + return AnyList::Reader(reader); +} + +template <> +inline AnyList::Builder DynamicList::Builder::as() { + return AnyList::Builder(builder); +} + +// ------------------------------------------------------------------- + +template +inline DynamicCapability::Client::Client(T&& client) + : Capability::Client(kj::mv(client)), schema(Schema::from>()) {} + +template +inline DynamicCapability::Client::Client(kj::Own&& server) + : Client(server->getSchema(), kj::mv(server)) {} +template +inline DynamicCapability::Client::Client(InterfaceSchema schema, kj::Own&& server) + : Capability::Client(kj::mv(server)), schema(schema) {} + +template +typename T::Client DynamicCapability::Client::as() { + static_assert(kind() == Kind::INTERFACE, + "DynamicCapability::Client::as() can only convert to interface types."); + schema.requireUsableAs(); + return typename T::Client(hook->addRef()); +} + +template +typename T::Client DynamicCapability::Client::releaseAs() { + static_assert(kind() == Kind::INTERFACE, + "DynamicCapability::Client::as() can only convert to interface types."); + schema.requireUsableAs(); + return typename T::Client(kj::mv(hook)); +} + +inline CallContext::CallContext( + CallContextHook& hook, StructSchema paramType, StructSchema resultType) + : hook(&hook), paramType(paramType), resultType(resultType) {} +inline DynamicStruct::Reader CallContext::getParams() { + return hook->getParams().getAs(paramType); +} +inline void CallContext::releaseParams() { + hook->releaseParams(); +} +inline DynamicStruct::Builder CallContext::getResults( + kj::Maybe sizeHint) { + return hook->getResults(sizeHint).getAs(resultType); +} +inline DynamicStruct::Builder CallContext::initResults( + kj::Maybe sizeHint) { + return hook->getResults(sizeHint).initAs(resultType); +} +inline void CallContext::setResults(DynamicStruct::Reader value) { + hook->getResults(value.totalSize()).setAs(value); +} +inline void CallContext::adoptResults(Orphan&& value) { + hook->getResults(MessageSize { 0, 0 }).adopt(kj::mv(value)); +} +inline Orphanage CallContext::getResultsOrphanage( + kj::Maybe sizeHint) { + return Orphanage::getForMessageContaining(hook->getResults(sizeHint)); +} +template +inline kj::Promise CallContext::tailCall( + Request&& tailRequest) { + return hook->tailCall(kj::mv(tailRequest.hook)); +} +inline void CallContext::allowCancellation() { + hook->allowCancellation(); +} + +template <> +inline DynamicCapability::Client Capability::Client::castAs( + InterfaceSchema schema) { + return DynamicCapability::Client(schema, hook->addRef()); +} + +// ------------------------------------------------------------------- + +template +ReaderFor ConstSchema::as() const { + return DynamicValue::Reader(*this).as(); +} + +} // namespace capnp + +#endif // CAPNP_DYNAMIC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/endian.h b/phonelibs/capnp-cpp/include/capnp/endian.h new file mode 100644 index 00000000000000..c5a6e63c5a9584 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/endian.h @@ -0,0 +1,309 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_ENDIAN_H_ +#define CAPNP_ENDIAN_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "common.h" +#include +#include // memcpy + +namespace capnp { +namespace _ { // private + +// WireValue +// +// Wraps a primitive value as it appears on the wire. Namely, values are little-endian on the +// wire, because little-endian is the most common endianness in modern CPUs. +// +// Note: In general, code that depends cares about byte ordering is bad. See: +// http://commandcenter.blogspot.com/2012/04/byte-order-fallacy.html +// Cap'n Proto is special because it is essentially doing compiler-like things, fussing over +// allocation and layout of memory, in order to squeeze out every last drop of performance. + +#if _MSC_VER +// Assume Windows is little-endian. +// +// TODO(msvc): This is ugly. Maybe refactor later checks to be based on CAPNP_BYTE_ORDER or +// CAPNP_SWAP_BYTES or something, and define that in turn based on _MSC_VER or the GCC +// intrinsics. + +#ifndef __ORDER_BIG_ENDIAN__ +#define __ORDER_BIG_ENDIAN__ 4321 +#endif +#ifndef __ORDER_LITTLE_ENDIAN__ +#define __ORDER_LITTLE_ENDIAN__ 1234 +#endif +#ifndef __BYTE_ORDER__ +#define __BYTE_ORDER__ __ORDER_LITTLE_ENDIAN__ +#endif +#endif + +#if CAPNP_REVERSE_ENDIAN +#define CAPNP_WIRE_BYTE_ORDER __ORDER_BIG_ENDIAN__ +#define CAPNP_OPPOSITE_OF_WIRE_BYTE_ORDER __ORDER_LITTLE_ENDIAN__ +#else +#define CAPNP_WIRE_BYTE_ORDER __ORDER_LITTLE_ENDIAN__ +#define CAPNP_OPPOSITE_OF_WIRE_BYTE_ORDER __ORDER_BIG_ENDIAN__ +#endif + +#if defined(__BYTE_ORDER__) && \ + __BYTE_ORDER__ == CAPNP_WIRE_BYTE_ORDER && \ + !CAPNP_DISABLE_ENDIAN_DETECTION +// CPU is little-endian. We can just read/write the memory directly. + +template +class DirectWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { return value; } + KJ_ALWAYS_INLINE(void set(T newValue)) { value = newValue; } + +private: + T value; +}; + +template +using WireValue = DirectWireValue; +// To prevent ODR problems when endian-test, endian-reverse-test, and endian-fallback-test are +// linked together, we define each implementation with a different name and define an alias to the +// one we want to use. + +#elif defined(__BYTE_ORDER__) && \ + __BYTE_ORDER__ == CAPNP_OPPOSITE_OF_WIRE_BYTE_ORDER && \ + defined(__GNUC__) && !CAPNP_DISABLE_ENDIAN_DETECTION +// Big-endian, but GCC's __builtin_bswap() is available. + +// TODO(perf): Use dedicated instructions to read little-endian data on big-endian CPUs that have +// them. + +// TODO(perf): Verify that this code optimizes reasonably. In particular, ensure that the +// compiler optimizes away the memcpy()s and keeps everything in registers. + +template +class SwappingWireValue; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { return value; } + KJ_ALWAYS_INLINE(void set(T newValue)) { value = newValue; } + +private: + T value; +}; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + // Not all platforms have __builtin_bswap16() for some reason. In particular, it is missing + // on gcc-4.7.3-cygwin32 (but present on gcc-4.8.1-cygwin64). + uint16_t swapped = (value << 8) | (value >> 8); + T result; + memcpy(&result, &swapped, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint16_t raw; + memcpy(&raw, &newValue, sizeof(T)); + // Not all platforms have __builtin_bswap16() for some reason. In particular, it is missing + // on gcc-4.7.3-cygwin32 (but present on gcc-4.8.1-cygwin64). + value = (raw << 8) | (raw >> 8); + } + +private: + uint16_t value; +}; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint32_t swapped = __builtin_bswap32(value); + T result; + memcpy(&result, &swapped, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint32_t raw; + memcpy(&raw, &newValue, sizeof(T)); + value = __builtin_bswap32(raw); + } + +private: + uint32_t value; +}; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint64_t swapped = __builtin_bswap64(value); + T result; + memcpy(&result, &swapped, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint64_t raw; + memcpy(&raw, &newValue, sizeof(T)); + value = __builtin_bswap64(raw); + } + +private: + uint64_t value; +}; + +template +using WireValue = SwappingWireValue; +// To prevent ODR problems when endian-test, endian-reverse-test, and endian-fallback-test are +// linked together, we define each implementation with a different name and define an alias to the +// one we want to use. + +#else +// Unknown endianness. Fall back to bit shifts. + +#if !CAPNP_DISABLE_ENDIAN_DETECTION +#if _MSC_VER +#pragma message("Couldn't detect endianness of your platform. Using unoptimized fallback implementation.") +#pragma message("Consider changing this code to detect your platform and send us a patch!") +#else +#warning "Couldn't detect endianness of your platform. Using unoptimized fallback implementation." +#warning "Consider changing this code to detect your platform and send us a patch!" +#endif +#endif // !CAPNP_DISABLE_ENDIAN_DETECTION + +template +class ShiftingWireValue; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { return value; } + KJ_ALWAYS_INLINE(void set(T newValue)) { value = newValue; } + +private: + T value; +}; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint16_t raw = (static_cast(bytes[0]) ) | + (static_cast(bytes[1]) << 8); + T result; + memcpy(&result, &raw, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint16_t raw; + memcpy(&raw, &newValue, sizeof(T)); + bytes[0] = raw; + bytes[1] = raw >> 8; + } + +private: + union { + byte bytes[2]; + uint16_t align; + }; +}; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint32_t raw = (static_cast(bytes[0]) ) | + (static_cast(bytes[1]) << 8) | + (static_cast(bytes[2]) << 16) | + (static_cast(bytes[3]) << 24); + T result; + memcpy(&result, &raw, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint32_t raw; + memcpy(&raw, &newValue, sizeof(T)); + bytes[0] = raw; + bytes[1] = raw >> 8; + bytes[2] = raw >> 16; + bytes[3] = raw >> 24; + } + +private: + union { + byte bytes[4]; + uint32_t align; + }; +}; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint64_t raw = (static_cast(bytes[0]) ) | + (static_cast(bytes[1]) << 8) | + (static_cast(bytes[2]) << 16) | + (static_cast(bytes[3]) << 24) | + (static_cast(bytes[4]) << 32) | + (static_cast(bytes[5]) << 40) | + (static_cast(bytes[6]) << 48) | + (static_cast(bytes[7]) << 56); + T result; + memcpy(&result, &raw, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint64_t raw; + memcpy(&raw, &newValue, sizeof(T)); + bytes[0] = raw; + bytes[1] = raw >> 8; + bytes[2] = raw >> 16; + bytes[3] = raw >> 24; + bytes[4] = raw >> 32; + bytes[5] = raw >> 40; + bytes[6] = raw >> 48; + bytes[7] = raw >> 56; + } + +private: + union { + byte bytes[8]; + uint64_t align; + }; +}; + +template +using WireValue = ShiftingWireValue; +// To prevent ODR problems when endian-test, endian-reverse-test, and endian-fallback-test are +// linked together, we define each implementation with a different name and define an alias to the +// one we want to use. + +#endif + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_ENDIAN_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/ez-rpc.h b/phonelibs/capnp-cpp/include/capnp/ez-rpc.h new file mode 100644 index 00000000000000..fba5ace5820255 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/ez-rpc.h @@ -0,0 +1,254 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_EZ_RPC_H_ +#define CAPNP_EZ_RPC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "rpc.h" +#include "message.h" + +struct sockaddr; + +namespace kj { class AsyncIoProvider; class LowLevelAsyncIoProvider; } + +namespace capnp { + +class EzRpcContext; + +class EzRpcClient { + // Super-simple interface for setting up a Cap'n Proto RPC client. Example: + // + // # Cap'n Proto schema + // interface Adder { + // add @0 (left :Int32, right :Int32) -> (value :Int32); + // } + // + // // C++ client + // int main() { + // capnp::EzRpcClient client("localhost:3456"); + // Adder::Client adder = client.getMain(); + // auto request = adder.addRequest(); + // request.setLeft(12); + // request.setRight(34); + // auto response = request.send().wait(client.getWaitScope()); + // assert(response.getValue() == 46); + // return 0; + // } + // + // // C++ server + // class AdderImpl final: public Adder::Server { + // public: + // kj::Promise add(AddContext context) override { + // auto params = context.getParams(); + // context.getResults().setValue(params.getLeft() + params.getRight()); + // return kj::READY_NOW; + // } + // }; + // + // int main() { + // capnp::EzRpcServer server(kj::heap(), "*:3456"); + // kj::NEVER_DONE.wait(server.getWaitScope()); + // } + // + // This interface is easy, but it hides a lot of useful features available from the lower-level + // classes: + // - The server can only export a small set of public, singleton capabilities under well-known + // string names. This is fine for transient services where no state needs to be kept between + // connections, but hides the power of Cap'n Proto when it comes to long-lived resources. + // - EzRpcClient/EzRpcServer automatically set up a `kj::EventLoop` and make it current for the + // thread. Only one `kj::EventLoop` can exist per thread, so you cannot use these interfaces + // if you wish to set up your own event loop. (However, you can safely create multiple + // EzRpcClient / EzRpcServer objects in a single thread; they will make sure to make no more + // than one EventLoop.) + // - These classes only support simple two-party connections, not multilateral VatNetworks. + // - These classes only support communication over a raw, unencrypted socket. If you want to + // build on an abstract stream (perhaps one which supports encryption), you must use the + // lower-level interfaces. + // + // Some of these restrictions will probably be lifted in future versions, but some things will + // always require using the low-level interfaces directly. If you are interested in working + // at a lower level, start by looking at these interfaces: + // - `kj::setupAsyncIo()` in `kj/async-io.h`. + // - `RpcSystem` in `capnp/rpc.h`. + // - `TwoPartyVatNetwork` in `capnp/rpc-twoparty.h`. + +public: + explicit EzRpcClient(kj::StringPtr serverAddress, uint defaultPort = 0, + ReaderOptions readerOpts = ReaderOptions()); + // Construct a new EzRpcClient and connect to the given address. The connection is formed in + // the background -- if it fails, calls to capabilities returned by importCap() will fail with an + // appropriate exception. + // + // `defaultPort` is the IP port number to use if `serverAddress` does not include it explicitly. + // If unspecified, the port is required in `serverAddress`. + // + // The address is parsed by `kj::Network` in `kj/async-io.h`. See that interface for more info + // on the address format, but basically it's what you'd expect. + // + // `readerOpts` is the ReaderOptions structure used to read each incoming message on the + // connection. Setting this may be necessary if you need to receive very large individual + // messages or messages. However, it is recommended that you instead think about how to change + // your protocol to send large data blobs in multiple small chunks -- this is much better for + // both security and performance. See `ReaderOptions` in `message.h` for more details. + + EzRpcClient(const struct sockaddr* serverAddress, uint addrSize, + ReaderOptions readerOpts = ReaderOptions()); + // Like the above constructor, but connects to an already-resolved socket address. Any address + // format supported by `kj::Network` in `kj/async-io.h` is accepted. + + explicit EzRpcClient(int socketFd, ReaderOptions readerOpts = ReaderOptions()); + // Create a client on top of an already-connected socket. + // `readerOpts` acts as in the first constructor. + + ~EzRpcClient() noexcept(false); + + template + typename Type::Client getMain(); + Capability::Client getMain(); + // Get the server's main (aka "bootstrap") interface. + + template + typename Type::Client importCap(kj::StringPtr name) + KJ_DEPRECATED("Change your server to export a main interface, then use getMain() instead."); + Capability::Client importCap(kj::StringPtr name) + KJ_DEPRECATED("Change your server to export a main interface, then use getMain() instead."); + // ** DEPRECATED ** + // + // Ask the sever for the capability with the given name. You may specify a type to automatically + // down-cast to that type. It is up to you to specify the correct expected type. + // + // Named interfaces are deprecated. The new preferred usage pattern is for the server to export + // a "main" interface which itself has methods for getting any other interfaces. + + kj::WaitScope& getWaitScope(); + // Get the `WaitScope` for the client's `EventLoop`, which allows you to synchronously wait on + // promises. + + kj::AsyncIoProvider& getIoProvider(); + // Get the underlying AsyncIoProvider set up by the RPC system. This is useful if you want + // to do some non-RPC I/O in asynchronous fashion. + + kj::LowLevelAsyncIoProvider& getLowLevelIoProvider(); + // Get the underlying LowLevelAsyncIoProvider set up by the RPC system. This is useful if you + // want to do some non-RPC I/O in asynchronous fashion. + +private: + struct Impl; + kj::Own impl; +}; + +class EzRpcServer { + // The server counterpart to `EzRpcClient`. See `EzRpcClient` for an example. + +public: + explicit EzRpcServer(Capability::Client mainInterface, kj::StringPtr bindAddress, + uint defaultPort = 0, ReaderOptions readerOpts = ReaderOptions()); + // Construct a new `EzRpcServer` that binds to the given address. An address of "*" means to + // bind to all local addresses. + // + // `defaultPort` is the IP port number to use if `serverAddress` does not include it explicitly. + // If unspecified, a port is chosen automatically, and you must call getPort() to find out what + // it is. + // + // The address is parsed by `kj::Network` in `kj/async-io.h`. See that interface for more info + // on the address format, but basically it's what you'd expect. + // + // The server might not begin listening immediately, especially if `bindAddress` needs to be + // resolved. If you need to wait until the server is definitely up, wait on the promise returned + // by `getPort()`. + // + // `readerOpts` is the ReaderOptions structure used to read each incoming message on the + // connection. Setting this may be necessary if you need to receive very large individual + // messages or messages. However, it is recommended that you instead think about how to change + // your protocol to send large data blobs in multiple small chunks -- this is much better for + // both security and performance. See `ReaderOptions` in `message.h` for more details. + + EzRpcServer(Capability::Client mainInterface, struct sockaddr* bindAddress, uint addrSize, + ReaderOptions readerOpts = ReaderOptions()); + // Like the above constructor, but binds to an already-resolved socket address. Any address + // format supported by `kj::Network` in `kj/async-io.h` is accepted. + + EzRpcServer(Capability::Client mainInterface, int socketFd, uint port, + ReaderOptions readerOpts = ReaderOptions()); + // Create a server on top of an already-listening socket (i.e. one on which accept() may be + // called). `port` is returned by `getPort()` -- it serves no other purpose. + // `readerOpts` acts as in the other two above constructors. + + explicit EzRpcServer(kj::StringPtr bindAddress, uint defaultPort = 0, + ReaderOptions readerOpts = ReaderOptions()) + KJ_DEPRECATED("Please specify a main interface for your server."); + EzRpcServer(struct sockaddr* bindAddress, uint addrSize, + ReaderOptions readerOpts = ReaderOptions()) + KJ_DEPRECATED("Please specify a main interface for your server."); + EzRpcServer(int socketFd, uint port, ReaderOptions readerOpts = ReaderOptions()) + KJ_DEPRECATED("Please specify a main interface for your server."); + + ~EzRpcServer() noexcept(false); + + void exportCap(kj::StringPtr name, Capability::Client cap); + // Export a capability publicly under the given name, so that clients can import it. + // + // Keep in mind that you can implicitly convert `kj::Own&&` to + // `Capability::Client`, so it's typical to pass something like + // `kj::heap()` as the second parameter. + + kj::Promise getPort(); + // Get the IP port number on which this server is listening. This promise won't resolve until + // the server is actually listening. If the address was not an IP address (e.g. it was a Unix + // domain socket) then getPort() resolves to zero. + + kj::WaitScope& getWaitScope(); + // Get the `WaitScope` for the client's `EventLoop`, which allows you to synchronously wait on + // promises. + + kj::AsyncIoProvider& getIoProvider(); + // Get the underlying AsyncIoProvider set up by the RPC system. This is useful if you want + // to do some non-RPC I/O in asynchronous fashion. + + kj::LowLevelAsyncIoProvider& getLowLevelIoProvider(); + // Get the underlying LowLevelAsyncIoProvider set up by the RPC system. This is useful if you + // want to do some non-RPC I/O in asynchronous fashion. + +private: + struct Impl; + kj::Own impl; +}; + +// ======================================================================================= +// inline implementation details + +template +inline typename Type::Client EzRpcClient::getMain() { + return getMain().castAs(); +} + +template +inline typename Type::Client EzRpcClient::importCap(kj::StringPtr name) { + return importCap(name).castAs(); +} + +} // namespace capnp + +#endif // CAPNP_EZ_RPC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/generated-header-support.h b/phonelibs/capnp-cpp/include/capnp/generated-header-support.h new file mode 100644 index 00000000000000..51b6dd7c113c63 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/generated-header-support.h @@ -0,0 +1,407 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file is included from all generated headers. + +#ifndef CAPNP_GENERATED_HEADER_SUPPORT_H_ +#define CAPNP_GENERATED_HEADER_SUPPORT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "raw-schema.h" +#include "layout.h" +#include "list.h" +#include "orphan.h" +#include "pointer-helpers.h" +#include "any.h" +#include +#include + +namespace capnp { + +class MessageBuilder; // So that it can be declared a friend. + +template +struct ToDynamic_; // Defined in dynamic.h, needs to be declared as everyone's friend. + +struct DynamicStruct; // So that it can be declared a friend. + +struct Capability; // To declare brandBindingFor() + +namespace _ { // private + +#if !CAPNP_LITE + +template +inline const RawSchema& rawSchema() { + return *CapnpPrivate::schema; +} +template ::typeId> +inline const RawSchema& rawSchema() { + return *schemas::EnumInfo::schema; +} + +template +inline const RawBrandedSchema& rawBrandedSchema() { + return *CapnpPrivate::brand(); +} +template ::typeId> +inline const RawBrandedSchema& rawBrandedSchema() { + return schemas::EnumInfo::schema->defaultBrand; +} + +template +struct ChooseBrand; +// If all of `Params` are `AnyPointer`, return the type's default brand. Otherwise, return a +// specific brand instance. TypeTag is the _capnpPrivate struct for the type in question. + +template +struct ChooseBrand { + // All params were AnyPointer. No specific brand needed. + static constexpr _::RawBrandedSchema const* brand() { return &TypeTag::schema->defaultBrand; } +}; + +template +struct ChooseBrand: public ChooseBrand {}; +// The first parameter is AnyPointer, so recurse to check the rest. + +template +struct ChooseBrand { + // At least one parameter is not AnyPointer, so use the specificBrand constant. + static constexpr _::RawBrandedSchema const* brand() { return &TypeTag::specificBrand; } +}; + +template ()> +struct BrandBindingFor_; + +#define HANDLE_TYPE(Type, which) \ + template <> \ + struct BrandBindingFor_ { \ + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { \ + return { which, listDepth, nullptr }; \ + } \ + } +HANDLE_TYPE(Void, 0); +HANDLE_TYPE(bool, 1); +HANDLE_TYPE(int8_t, 2); +HANDLE_TYPE(int16_t, 3); +HANDLE_TYPE(int32_t, 4); +HANDLE_TYPE(int64_t, 5); +HANDLE_TYPE(uint8_t, 6); +HANDLE_TYPE(uint16_t, 7); +HANDLE_TYPE(uint32_t, 8); +HANDLE_TYPE(uint64_t, 9); +HANDLE_TYPE(float, 10); +HANDLE_TYPE(double, 11); +#undef HANDLE_TYPE + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 12, listDepth, nullptr }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 13, listDepth, nullptr }; + } +}; + +template +struct BrandBindingFor_, Kind::LIST> { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return BrandBindingFor_::get(listDepth + 1); + } +}; + +template +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 15, listDepth, nullptr }; + } +}; + +template +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 16, listDepth, T::_capnpPrivate::brand() }; + } +}; + +template +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 17, listDepth, T::_capnpPrivate::brand() }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 0 }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 1 }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 2 }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 3 }; + } +}; + +template +constexpr RawBrandedSchema::Binding brandBindingFor() { + return BrandBindingFor_::get(0); +} + +kj::StringTree structString(StructReader reader, const RawBrandedSchema& schema); +kj::String enumString(uint16_t value, const RawBrandedSchema& schema); +// Declared here so that we can declare inline stringify methods on generated types. +// Defined in stringify.c++, which depends on dynamic.c++, which is allowed not to be linked in. + +template +inline kj::StringTree structString(StructReader reader) { + return structString(reader, rawBrandedSchema()); +} +template +inline kj::String enumString(T value) { + return enumString(static_cast(value), rawBrandedSchema()); +} + +#endif // !CAPNP_LITE + +// TODO(cleanup): Unify ConstStruct and ConstList. +template +class ConstStruct { +public: + ConstStruct() = delete; + KJ_DISALLOW_COPY(ConstStruct); + inline explicit constexpr ConstStruct(const word* ptr): ptr(ptr) {} + + inline typename T::Reader get() const { + return AnyPointer::Reader(PointerReader::getRootUnchecked(ptr)).getAs(); + } + + inline operator typename T::Reader() const { return get(); } + inline typename T::Reader operator*() const { return get(); } + inline TemporaryPointer operator->() const { return get(); } + +private: + const word* ptr; +}; + +template +class ConstList { +public: + ConstList() = delete; + KJ_DISALLOW_COPY(ConstList); + inline explicit constexpr ConstList(const word* ptr): ptr(ptr) {} + + inline typename List::Reader get() const { + return AnyPointer::Reader(PointerReader::getRootUnchecked(ptr)).getAs>(); + } + + inline operator typename List::Reader() const { return get(); } + inline typename List::Reader operator*() const { return get(); } + inline TemporaryPointer::Reader> operator->() const { return get(); } + +private: + const word* ptr; +}; + +template +class ConstText { +public: + ConstText() = delete; + KJ_DISALLOW_COPY(ConstText); + inline explicit constexpr ConstText(const word* ptr): ptr(ptr) {} + + inline Text::Reader get() const { + return Text::Reader(reinterpret_cast(ptr), size); + } + + inline operator Text::Reader() const { return get(); } + inline Text::Reader operator*() const { return get(); } + inline TemporaryPointer operator->() const { return get(); } + + inline kj::StringPtr toString() const { + return get(); + } + +private: + const word* ptr; +}; + +template +inline kj::StringPtr KJ_STRINGIFY(const ConstText& s) { + return s.get(); +} + +template +class ConstData { +public: + ConstData() = delete; + KJ_DISALLOW_COPY(ConstData); + inline explicit constexpr ConstData(const word* ptr): ptr(ptr) {} + + inline Data::Reader get() const { + return Data::Reader(reinterpret_cast(ptr), size); + } + + inline operator Data::Reader() const { return get(); } + inline Data::Reader operator*() const { return get(); } + inline TemporaryPointer operator->() const { return get(); } + +private: + const word* ptr; +}; + +template +inline auto KJ_STRINGIFY(const ConstData& s) -> decltype(kj::toCharSequence(s.get())) { + return kj::toCharSequence(s.get()); +} + +} // namespace _ (private) + +template +inline constexpr uint64_t typeId() { return CapnpPrivate::typeId; } +template ::typeId> +inline constexpr uint64_t typeId() { return id; } +// typeId() returns the type ID as defined in the schema. Works with structs, enums, and +// interfaces. + +template +inline constexpr uint sizeInWords() { + // Return the size, in words, of a Struct type, if allocated free-standing (not in a list). + // May be useful for pre-computing space needed in order to precisely allocate messages. + + return unbound((upgradeBound(_::structSize().data) + + _::structSize().pointers * WORDS_PER_POINTER) / WORDS); +} + +} // namespace capnp + +#if _MSC_VER +// MSVC doesn't understand floating-point constexpr yet. +// +// TODO(msvc): Remove this hack when MSVC is fixed. +#define CAPNP_NON_INT_CONSTEXPR_DECL_INIT(value) +#define CAPNP_NON_INT_CONSTEXPR_DEF_INIT(value) = value +#else +#define CAPNP_NON_INT_CONSTEXPR_DECL_INIT(value) = value +#define CAPNP_NON_INT_CONSTEXPR_DEF_INIT(value) +#endif + +#if _MSC_VER +// TODO(msvc): A little hack to allow MSVC to use C++14 return type deduction in cases where the +// explicit type exposes bugs in the compiler. +#define CAPNP_AUTO_IF_MSVC(...) auto +#else +#define CAPNP_AUTO_IF_MSVC(...) __VA_ARGS__ +#endif + +#if CAPNP_LITE + +#define CAPNP_DECLARE_SCHEMA(id) \ + extern ::capnp::word const* const bp_##id + +#define CAPNP_DECLARE_ENUM(type, id) \ + inline ::kj::String KJ_STRINGIFY(type##_##id value) { \ + return ::kj::str(static_cast(value)); \ + } \ + template <> struct EnumInfo { \ + struct IsEnum; \ + static constexpr uint64_t typeId = 0x##id; \ + static inline ::capnp::word const* encodedSchema() { return bp_##id; } \ + } + +#if _MSC_VER +// TODO(msvc): MSVC dosen't expect constexprs to have definitions. +#define CAPNP_DEFINE_ENUM(type, id) +#else +#define CAPNP_DEFINE_ENUM(type, id) \ + constexpr uint64_t EnumInfo::typeId +#endif + +#define CAPNP_DECLARE_STRUCT_HEADER(id, dataWordSize_, pointerCount_) \ + struct IsStruct; \ + static constexpr uint64_t typeId = 0x##id; \ + static constexpr uint16_t dataWordSize = dataWordSize_; \ + static constexpr uint16_t pointerCount = pointerCount_; \ + static inline ::capnp::word const* encodedSchema() { return ::capnp::schemas::bp_##id; } + +#else // CAPNP_LITE + +#define CAPNP_DECLARE_SCHEMA(id) \ + extern ::capnp::word const* const bp_##id; \ + extern const ::capnp::_::RawSchema s_##id + +#define CAPNP_DECLARE_ENUM(type, id) \ + inline ::kj::String KJ_STRINGIFY(type##_##id value) { \ + return ::capnp::_::enumString(value); \ + } \ + template <> struct EnumInfo { \ + struct IsEnum; \ + static constexpr uint64_t typeId = 0x##id; \ + static inline ::capnp::word const* encodedSchema() { return bp_##id; } \ + static constexpr ::capnp::_::RawSchema const* schema = &s_##id; \ + } +#define CAPNP_DEFINE_ENUM(type, id) \ + constexpr uint64_t EnumInfo::typeId; \ + constexpr ::capnp::_::RawSchema const* EnumInfo::schema + +#define CAPNP_DECLARE_STRUCT_HEADER(id, dataWordSize_, pointerCount_) \ + struct IsStruct; \ + static constexpr uint64_t typeId = 0x##id; \ + static constexpr ::capnp::Kind kind = ::capnp::Kind::STRUCT; \ + static constexpr uint16_t dataWordSize = dataWordSize_; \ + static constexpr uint16_t pointerCount = pointerCount_; \ + static inline ::capnp::word const* encodedSchema() { return ::capnp::schemas::bp_##id; } \ + static constexpr ::capnp::_::RawSchema const* schema = &::capnp::schemas::s_##id; + +#define CAPNP_DECLARE_INTERFACE_HEADER(id) \ + struct IsInterface; \ + static constexpr uint64_t typeId = 0x##id; \ + static constexpr ::capnp::Kind kind = ::capnp::Kind::INTERFACE; \ + static inline ::capnp::word const* encodedSchema() { return ::capnp::schemas::bp_##id; } \ + static constexpr ::capnp::_::RawSchema const* schema = &::capnp::schemas::s_##id; + +#endif // CAPNP_LITE, else + +#endif // CAPNP_GENERATED_HEADER_SUPPORT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/json.capnp b/phonelibs/capnp-cpp/include/capnp/json.capnp new file mode 100644 index 00000000000000..55188736f8bdb2 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/json.capnp @@ -0,0 +1,58 @@ +# Copyright (c) 2015 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0x8ef99297a43a5e34; + +$import "/capnp/c++.capnp".namespace("capnp"); + +struct JsonValue { + union { + null @0 :Void; + boolean @1 :Bool; + number @2 :Float64; + string @3 :Text; + array @4 :List(JsonValue); + object @5 :List(Field); + # Standard JSON values. + + call @6 :Call; + # Non-standard: A "function call", applying a named function (named by a single identifier) + # to a parameter list. Examples: + # + # BinData(0, "Zm9vCg==") + # ISODate("2015-04-15T08:44:50.218Z") + # + # Mongo DB users will recognize the above as exactly the syntax Mongo uses to represent BSON + # "binary" and "date" types in text, since JSON has no analog of these. This is basically the + # reason this extension exists. We do NOT recommend using `call` unless you specifically need + # to be compatible with some silly format that uses this syntax. + } + + struct Field { + name @0 :Text; + value @1 :JsonValue; + } + + struct Call { + function @0 :Text; + params @1 :List(JsonValue); + } +} diff --git a/phonelibs/capnp-cpp/include/capnp/layout.h b/phonelibs/capnp-cpp/include/capnp/layout.h new file mode 100644 index 00000000000000..99dc533b2bf157 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/layout.h @@ -0,0 +1,1274 @@ +// Copyright (c) 2013-2016 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file is NOT intended for use by clients, except in generated code. +// +// This file defines low-level, non-type-safe classes for traversing the Cap'n Proto memory layout +// (which is also its wire format). Code generated by the Cap'n Proto compiler uses these classes, +// as does other parts of the Cap'n proto library which provide a higher-level interface for +// dynamic introspection. + +#ifndef CAPNP_LAYOUT_H_ +#define CAPNP_LAYOUT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include +#include "common.h" +#include "blob.h" +#include "endian.h" + +#if (defined(__mips__) || defined(__hppa__)) && !defined(CAPNP_CANONICALIZE_NAN) +#define CAPNP_CANONICALIZE_NAN 1 +// Explicitly detect NaNs and canonicalize them to the quiet NaN value as would be returned by +// __builtin_nan("") on systems implementing the IEEE-754 recommended (but not required) NaN +// signalling/quiet differentiation (such as x86). Unfortunately, some architectures -- in +// particular, MIPS -- represent quiet vs. signalling nans differently than the rest of the world. +// Canonicalizing them makes output consistent (which is important!), but hurts performance +// slightly. +// +// Note that trying to convert MIPS NaNs to standard NaNs without losing data doesn't work. +// Signaling vs. quiet is indicated by a bit, with the meaning being the opposite on MIPS vs. +// everyone else. It would be great if we could just flip that bit, but we can't, because if the +// significand is all-zero, then the value is infinity rather than NaN. This means that on most +// machines, where the bit indicates quietness, there is one more quiet NaN value than signalling +// NaN value, whereas on MIPS there is one more sNaN than qNaN, and thus there is no isomorphic +// mapping that properly preserves quietness. Instead of doing something hacky, we just give up +// and blow away NaN payloads, because no one uses them anyway. +#endif + +namespace capnp { + +#if !CAPNP_LITE +class ClientHook; +#endif // !CAPNP_LITE + +namespace _ { // private + +class PointerBuilder; +class PointerReader; +class StructBuilder; +class StructReader; +class ListBuilder; +class ListReader; +class OrphanBuilder; +struct WirePointer; +struct WireHelpers; +class SegmentReader; +class SegmentBuilder; +class Arena; +class BuilderArena; + +// ============================================================================= + +#if CAPNP_DEBUG_TYPES +typedef kj::UnitRatio, BitLabel, ElementLabel> BitsPerElementTableType; +#else +typedef uint BitsPerElementTableType; +#endif + +static constexpr BitsPerElementTableType BITS_PER_ELEMENT_TABLE[8] = { + bounded< 0>() * BITS / ELEMENTS, + bounded< 1>() * BITS / ELEMENTS, + bounded< 8>() * BITS / ELEMENTS, + bounded<16>() * BITS / ELEMENTS, + bounded<32>() * BITS / ELEMENTS, + bounded<64>() * BITS / ELEMENTS, + bounded< 0>() * BITS / ELEMENTS, + bounded< 0>() * BITS / ELEMENTS +}; + +inline KJ_CONSTEXPR() BitsPerElementTableType dataBitsPerElement(ElementSize size) { + return _::BITS_PER_ELEMENT_TABLE[static_cast(size)]; +} + +inline constexpr PointersPerElementN<1> pointersPerElement(ElementSize size) { + return size == ElementSize::POINTER + ? PointersPerElementN<1>(ONE * POINTERS / ELEMENTS) + : PointersPerElementN<1>(ZERO * POINTERS / ELEMENTS); +} + +static constexpr BitsPerElementTableType BITS_PER_ELEMENT_INCLUDING_PONITERS_TABLE[8] = { + bounded< 0>() * BITS / ELEMENTS, + bounded< 1>() * BITS / ELEMENTS, + bounded< 8>() * BITS / ELEMENTS, + bounded<16>() * BITS / ELEMENTS, + bounded<32>() * BITS / ELEMENTS, + bounded<64>() * BITS / ELEMENTS, + bounded<64>() * BITS / ELEMENTS, + bounded< 0>() * BITS / ELEMENTS +}; + +inline KJ_CONSTEXPR() BitsPerElementTableType bitsPerElementIncludingPointers(ElementSize size) { + return _::BITS_PER_ELEMENT_INCLUDING_PONITERS_TABLE[static_cast(size)]; +} + +template struct ElementSizeForByteSize; +template <> struct ElementSizeForByteSize<1> { static constexpr ElementSize value = ElementSize::BYTE; }; +template <> struct ElementSizeForByteSize<2> { static constexpr ElementSize value = ElementSize::TWO_BYTES; }; +template <> struct ElementSizeForByteSize<4> { static constexpr ElementSize value = ElementSize::FOUR_BYTES; }; +template <> struct ElementSizeForByteSize<8> { static constexpr ElementSize value = ElementSize::EIGHT_BYTES; }; + +template struct ElementSizeForType { + static constexpr ElementSize value = + // Primitive types that aren't special-cased below can be determined from sizeof(). + CAPNP_KIND(T) == Kind::PRIMITIVE ? ElementSizeForByteSize::value : + CAPNP_KIND(T) == Kind::ENUM ? ElementSize::TWO_BYTES : + CAPNP_KIND(T) == Kind::STRUCT ? ElementSize::INLINE_COMPOSITE : + + // Everything else is a pointer. + ElementSize::POINTER; +}; + +// Void and bool are special. +template <> struct ElementSizeForType { static constexpr ElementSize value = ElementSize::VOID; }; +template <> struct ElementSizeForType { static constexpr ElementSize value = ElementSize::BIT; }; + +// Lists and blobs are pointers, not structs. +template struct ElementSizeForType> { + static constexpr ElementSize value = ElementSize::POINTER; +}; +template <> struct ElementSizeForType { + static constexpr ElementSize value = ElementSize::POINTER; +}; +template <> struct ElementSizeForType { + static constexpr ElementSize value = ElementSize::POINTER; +}; + +template +inline constexpr ElementSize elementSizeForType() { + return ElementSizeForType::value; +} + +struct MessageSizeCounts { + WordCountN<61, uint64_t> wordCount; // 2^64 bytes + uint capCount; + + MessageSizeCounts& operator+=(const MessageSizeCounts& other) { + // OK to truncate unchecked because this class is used to count actual stuff in memory, and + // we couldn't possibly have anywhere near 2^61 words. + wordCount = assumeBits<61>(wordCount + other.wordCount); + capCount += other.capCount; + return *this; + } + + void addWords(WordCountN<61, uint64_t> other) { + wordCount = assumeBits<61>(wordCount + other); + } + + MessageSize asPublic() { + return MessageSize { unbound(wordCount / WORDS), capCount }; + } +}; + +// ============================================================================= + +template +union AlignedData { + // Useful for declaring static constant data blobs as an array of bytes, but forcing those + // bytes to be word-aligned. + + uint8_t bytes[wordCount * sizeof(word)]; + word words[wordCount]; +}; + +struct StructSize { + StructDataWordCount data; + StructPointerCount pointers; + + inline constexpr WordCountN<17> total() const { return data + pointers * WORDS_PER_POINTER; } + + StructSize() = default; + inline constexpr StructSize(StructDataWordCount data, StructPointerCount pointers) + : data(data), pointers(pointers) {} +}; + +template +inline constexpr StructSize structSize() { + return StructSize(bounded(CapnpPrivate::dataWordSize) * WORDS, + bounded(CapnpPrivate::pointerCount) * POINTERS); +} + +template > +inline constexpr StructSize minStructSizeForElement() { + // If T is a struct, return its struct size. Otherwise return the minimum struct size big enough + // to hold a T. + + return StructSize(bounded(CapnpPrivate::dataWordSize) * WORDS, + bounded(CapnpPrivate::pointerCount) * POINTERS); +} + +template > +inline constexpr StructSize minStructSizeForElement() { + // If T is a struct, return its struct size. Otherwise return the minimum struct size big enough + // to hold a T. + + return StructSize( + dataBitsPerElement(elementSizeForType()) * ELEMENTS > ZERO * BITS + ? StructDataWordCount(ONE * WORDS) : StructDataWordCount(ZERO * WORDS), + pointersPerElement(elementSizeForType()) * ELEMENTS); +} + +// ------------------------------------------------------------------- +// Masking of default values + +template struct Mask_; +template struct Mask_ { typedef T Type; }; +template struct Mask_ { typedef uint16_t Type; }; +template <> struct Mask_ { typedef uint32_t Type; }; +template <> struct Mask_ { typedef uint64_t Type; }; + +template struct Mask_ { + // Union discriminants end up here. + static_assert(sizeof(T) == 2, "Don't know how to mask this type."); + typedef uint16_t Type; +}; + +template +using Mask = typename Mask_::Type; + +template +KJ_ALWAYS_INLINE(Mask mask(T value, Mask mask)); +template +KJ_ALWAYS_INLINE(T unmask(Mask value, Mask mask)); + +template +inline Mask mask(T value, Mask mask) { + return static_cast >(value) ^ mask; +} + +template <> +inline uint32_t mask(float value, uint32_t mask) { +#if CAPNP_CANONICALIZE_NAN + if (value != value) { + return 0x7fc00000u ^ mask; + } +#endif + + uint32_t i; + static_assert(sizeof(i) == sizeof(value), "float is not 32 bits?"); + memcpy(&i, &value, sizeof(value)); + return i ^ mask; +} + +template <> +inline uint64_t mask(double value, uint64_t mask) { +#if CAPNP_CANONICALIZE_NAN + if (value != value) { + return 0x7ff8000000000000ull ^ mask; + } +#endif + + uint64_t i; + static_assert(sizeof(i) == sizeof(value), "double is not 64 bits?"); + memcpy(&i, &value, sizeof(value)); + return i ^ mask; +} + +template +inline T unmask(Mask value, Mask mask) { + return static_cast(value ^ mask); +} + +template <> +inline float unmask(uint32_t value, uint32_t mask) { + value ^= mask; + float result; + static_assert(sizeof(result) == sizeof(value), "float is not 32 bits?"); + memcpy(&result, &value, sizeof(value)); + return result; +} + +template <> +inline double unmask(uint64_t value, uint64_t mask) { + value ^= mask; + double result; + static_assert(sizeof(result) == sizeof(value), "double is not 64 bits?"); + memcpy(&result, &value, sizeof(value)); + return result; +} + +// ------------------------------------------------------------------- + +class CapTableReader { +public: +#if !CAPNP_LITE + virtual kj::Maybe> extractCap(uint index) = 0; + // Extract the capability at the given index. If the index is invalid, returns null. +#endif // !CAPNP_LITE +}; + +class CapTableBuilder: public CapTableReader { +public: +#if !CAPNP_LITE + virtual uint injectCap(kj::Own&& cap) = 0; + // Add the capability to the message and return its index. If the same ClientHook is injected + // twice, this may return the same index both times, but in this case dropCap() needs to be + // called an equal number of times to actually remove the cap. + + virtual void dropCap(uint index) = 0; + // Remove a capability injected earlier. Called when the pointer is overwritten or zero'd out. +#endif // !CAPNP_LITE +}; + +// ------------------------------------------------------------------- + +class PointerBuilder: public kj::DisallowConstCopy { + // Represents a single pointer, usually embedded in a struct or a list. + +public: + inline PointerBuilder(): segment(nullptr), capTable(nullptr), pointer(nullptr) {} + + static inline PointerBuilder getRoot( + SegmentBuilder* segment, CapTableBuilder* capTable, word* location); + // Get a PointerBuilder representing a message root located in the given segment at the given + // location. + + inline bool isNull() { return getPointerType() == PointerType::NULL_; } + PointerType getPointerType() const; + + StructBuilder getStruct(StructSize size, const word* defaultValue); + ListBuilder getList(ElementSize elementSize, const word* defaultValue); + ListBuilder getStructList(StructSize elementSize, const word* defaultValue); + ListBuilder getListAnySize(const word* defaultValue); + template typename T::Builder getBlob( + const void* defaultValue, ByteCount defaultSize); +#if !CAPNP_LITE + kj::Own getCapability(); +#endif // !CAPNP_LITE + // Get methods: Get the value. If it is null, initialize it to a copy of the default value. + // The default value is encoded as an "unchecked message" for structs, lists, and objects, or a + // simple byte array for blobs. + + StructBuilder initStruct(StructSize size); + ListBuilder initList(ElementSize elementSize, ElementCount elementCount); + ListBuilder initStructList(ElementCount elementCount, StructSize size); + template typename T::Builder initBlob(ByteCount size); + // Init methods: Initialize the pointer to a newly-allocated object, discarding the existing + // object. + + void setStruct(const StructReader& value, bool canonical = false); + void setList(const ListReader& value, bool canonical = false); + template void setBlob(typename T::Reader value); +#if !CAPNP_LITE + void setCapability(kj::Own&& cap); +#endif // !CAPNP_LITE + // Set methods: Initialize the pointer to a newly-allocated copy of the given value, discarding + // the existing object. + + void adopt(OrphanBuilder&& orphan); + // Set the pointer to point at the given orphaned value. + + OrphanBuilder disown(); + // Set the pointer to null and return its previous value as an orphan. + + void clear(); + // Clear the pointer to null, discarding its previous value. + + void transferFrom(PointerBuilder other); + // Equivalent to `adopt(other.disown())`. + + void copyFrom(PointerReader other, bool canonical = false); + // Equivalent to `set(other.get())`. + // If you set the canonical flag, it will attempt to lay the target out + // canonically, provided enough space is available. + + PointerReader asReader() const; + + BuilderArena* getArena() const; + // Get the arena containing this pointer. + + CapTableBuilder* getCapTable(); + // Gets the capability context in which this object is operating. + + PointerBuilder imbue(CapTableBuilder* capTable); + // Return a copy of this builder except using the given capability context. + +private: + SegmentBuilder* segment; // Memory segment in which the pointer resides. + CapTableBuilder* capTable; // Table of capability indexes. + WirePointer* pointer; // Pointer to the pointer. + + inline PointerBuilder(SegmentBuilder* segment, CapTableBuilder* capTable, WirePointer* pointer) + : segment(segment), capTable(capTable), pointer(pointer) {} + + friend class StructBuilder; + friend class ListBuilder; + friend class OrphanBuilder; +}; + +class PointerReader { +public: + inline PointerReader() + : segment(nullptr), capTable(nullptr), pointer(nullptr), nestingLimit(0x7fffffff) {} + + static PointerReader getRoot(SegmentReader* segment, CapTableReader* capTable, + const word* location, int nestingLimit); + // Get a PointerReader representing a message root located in the given segment at the given + // location. + + static inline PointerReader getRootUnchecked(const word* location); + // Get a PointerReader for an unchecked message. + + MessageSizeCounts targetSize() const; + // Return the total size of the target object and everything to which it points. Does not count + // far pointer overhead. This is useful for deciding how much space is needed to copy the object + // into a flat array. However, the caller is advised NOT to treat this value as secure. Instead, + // use the result as a hint for allocating the first segment, do the copy, and then throw an + // exception if it overruns. + + inline bool isNull() const { return getPointerType() == PointerType::NULL_; } + PointerType getPointerType() const; + + StructReader getStruct(const word* defaultValue) const; + ListReader getList(ElementSize expectedElementSize, const word* defaultValue) const; + ListReader getListAnySize(const word* defaultValue) const; + template + typename T::Reader getBlob(const void* defaultValue, ByteCount defaultSize) const; +#if !CAPNP_LITE + kj::Own getCapability() const; +#endif // !CAPNP_LITE + // Get methods: Get the value. If it is null, return the default value instead. + // The default value is encoded as an "unchecked message" for structs, lists, and objects, or a + // simple byte array for blobs. + + const word* getUnchecked() const; + // If this is an unchecked message, get a word* pointing at the location of the pointer. This + // word* can actually be passed to readUnchecked() to read the designated sub-object later. If + // this isn't an unchecked message, throws an exception. + + kj::Maybe getArena() const; + // Get the arena containing this pointer. + + CapTableReader* getCapTable(); + // Gets the capability context in which this object is operating. + + PointerReader imbue(CapTableReader* capTable) const; + // Return a copy of this reader except using the given capability context. + + bool isCanonical(const word **readHead); + // Validate this pointer's canonicity, subject to the conditions: + // * All data to the left of readHead has been read thus far (for pointer + // ordering) + // * All pointers in preorder have already been checked + // * This pointer is in the first and only segment of the message + +private: + SegmentReader* segment; // Memory segment in which the pointer resides. + CapTableReader* capTable; // Table of capability indexes. + const WirePointer* pointer; // Pointer to the pointer. null = treat as null pointer. + + int nestingLimit; + // Limits the depth of message structures to guard against stack-overflow-based DoS attacks. + // Once this reaches zero, further pointers will be pruned. + + inline PointerReader(SegmentReader* segment, CapTableReader* capTable, + const WirePointer* pointer, int nestingLimit) + : segment(segment), capTable(capTable), pointer(pointer), nestingLimit(nestingLimit) {} + + friend class StructReader; + friend class ListReader; + friend class PointerBuilder; + friend class OrphanBuilder; +}; + +// ------------------------------------------------------------------- + +class StructBuilder: public kj::DisallowConstCopy { +public: + inline StructBuilder(): segment(nullptr), capTable(nullptr), data(nullptr), pointers(nullptr) {} + + inline word* getLocation() { return reinterpret_cast(data); } + // Get the object's location. Only valid for independently-allocated objects (i.e. not list + // elements). + + inline StructDataBitCount getDataSectionSize() const { return dataSize; } + inline StructPointerCount getPointerSectionSize() const { return pointerCount; } + inline kj::ArrayPtr getDataSectionAsBlob(); + inline _::ListBuilder getPointerSectionAsList(); + + template + KJ_ALWAYS_INLINE(bool hasDataField(StructDataOffset offset)); + // Return true if the field is set to something other than its default value. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset)); + // Gets the data field value of the given type at the given offset. The offset is measured in + // multiples of the field size, determined by the type. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset, Mask mask)); + // Like getDataField() but applies the given XOR mask to the data on load. Used for reading + // fields with non-zero default values. + + template + KJ_ALWAYS_INLINE(void setDataField(StructDataOffset offset, kj::NoInfer value)); + // Sets the data field value at the given offset. + + template + KJ_ALWAYS_INLINE(void setDataField(StructDataOffset offset, + kj::NoInfer value, Mask mask)); + // Like setDataField() but applies the given XOR mask before storing. Used for writing fields + // with non-zero default values. + + KJ_ALWAYS_INLINE(PointerBuilder getPointerField(StructPointerOffset ptrIndex)); + // Get a builder for a pointer field given the index within the pointer section. + + void clearAll(); + // Clear all pointers and data. + + void transferContentFrom(StructBuilder other); + // Adopt all pointers from `other`, and also copy all data. If `other`'s sections are larger + // than this, the extra data is not transferred, meaning there is a risk of data loss when + // transferring from messages built with future versions of the protocol. + + void copyContentFrom(StructReader other); + // Copy content from `other`. If `other`'s sections are larger than this, the extra data is not + // copied, meaning there is a risk of data loss when copying from messages built with future + // versions of the protocol. + + StructReader asReader() const; + // Gets a StructReader pointing at the same memory. + + BuilderArena* getArena(); + // Gets the arena in which this object is allocated. + + CapTableBuilder* getCapTable(); + // Gets the capability context in which this object is operating. + + StructBuilder imbue(CapTableBuilder* capTable); + // Return a copy of this builder except using the given capability context. + +private: + SegmentBuilder* segment; // Memory segment in which the struct resides. + CapTableBuilder* capTable; // Table of capability indexes. + void* data; // Pointer to the encoded data. + WirePointer* pointers; // Pointer to the encoded pointers. + + StructDataBitCount dataSize; + // Size of data section. We use a bit count rather than a word count to more easily handle the + // case of struct lists encoded with less than a word per element. + + StructPointerCount pointerCount; // Size of the pointer section. + + inline StructBuilder(SegmentBuilder* segment, CapTableBuilder* capTable, + void* data, WirePointer* pointers, + StructDataBitCount dataSize, StructPointerCount pointerCount) + : segment(segment), capTable(capTable), data(data), pointers(pointers), + dataSize(dataSize), pointerCount(pointerCount) {} + + friend class ListBuilder; + friend struct WireHelpers; + friend class OrphanBuilder; +}; + +class StructReader { +public: + inline StructReader() + : segment(nullptr), capTable(nullptr), data(nullptr), pointers(nullptr), + dataSize(ZERO * BITS), pointerCount(ZERO * POINTERS), nestingLimit(0x7fffffff) {} + inline StructReader(kj::ArrayPtr data) + : segment(nullptr), capTable(nullptr), data(data.begin()), pointers(nullptr), + dataSize(assumeBits(data.size()) * WORDS * BITS_PER_WORD), + pointerCount(ZERO * POINTERS), nestingLimit(0x7fffffff) {} + + const void* getLocation() const { return data; } + + inline StructDataBitCount getDataSectionSize() const { return dataSize; } + inline StructPointerCount getPointerSectionSize() const { return pointerCount; } + inline kj::ArrayPtr getDataSectionAsBlob(); + inline _::ListReader getPointerSectionAsList(); + + kj::Array canonicalize(); + + template + KJ_ALWAYS_INLINE(bool hasDataField(StructDataOffset offset) const); + // Return true if the field is set to something other than its default value. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset) const); + // Get the data field value of the given type at the given offset. The offset is measured in + // multiples of the field size, determined by the type. Returns zero if the offset is past the + // end of the struct's data section. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset, Mask mask) const); + // Like getDataField(offset), but applies the given XOR mask to the result. Used for reading + // fields with non-zero default values. + + KJ_ALWAYS_INLINE(PointerReader getPointerField(StructPointerOffset ptrIndex) const); + // Get a reader for a pointer field given the index within the pointer section. If the index + // is out-of-bounds, returns a null pointer. + + MessageSizeCounts totalSize() const; + // Return the total size of the struct and everything to which it points. Does not count far + // pointer overhead. This is useful for deciding how much space is needed to copy the struct + // into a flat array. However, the caller is advised NOT to treat this value as secure. Instead, + // use the result as a hint for allocating the first segment, do the copy, and then throw an + // exception if it overruns. + + CapTableReader* getCapTable(); + // Gets the capability context in which this object is operating. + + StructReader imbue(CapTableReader* capTable) const; + // Return a copy of this reader except using the given capability context. + + bool isCanonical(const word **readHead, const word **ptrHead, + bool *dataTrunc, bool *ptrTrunc); + // Validate this pointer's canonicity, subject to the conditions: + // * All data to the left of readHead has been read thus far (for pointer + // ordering) + // * All pointers in preorder have already been checked + // * This pointer is in the first and only segment of the message + // + // If this function returns false, the struct is non-canonical. If it + // returns true, then: + // * If it is a composite in a list, it is canonical if at least one struct + // in the list outputs dataTrunc = 1, and at least one outputs ptrTrunc = 1 + // * If it is derived from a struct pointer, it is canonical if + // dataTrunc = 1 AND ptrTrunc = 1 + +private: + SegmentReader* segment; // Memory segment in which the struct resides. + CapTableReader* capTable; // Table of capability indexes. + + const void* data; + const WirePointer* pointers; + + StructDataBitCount dataSize; + // Size of data section. We use a bit count rather than a word count to more easily handle the + // case of struct lists encoded with less than a word per element. + + StructPointerCount pointerCount; // Size of the pointer section. + + int nestingLimit; + // Limits the depth of message structures to guard against stack-overflow-based DoS attacks. + // Once this reaches zero, further pointers will be pruned. + // TODO(perf): Limit to 16 bits for better packing? + + inline StructReader(SegmentReader* segment, CapTableReader* capTable, + const void* data, const WirePointer* pointers, + StructDataBitCount dataSize, StructPointerCount pointerCount, + int nestingLimit) + : segment(segment), capTable(capTable), data(data), pointers(pointers), + dataSize(dataSize), pointerCount(pointerCount), + nestingLimit(nestingLimit) {} + + friend class ListReader; + friend class StructBuilder; + friend struct WireHelpers; +}; + +// ------------------------------------------------------------------- + +class ListBuilder: public kj::DisallowConstCopy { +public: + inline explicit ListBuilder(ElementSize elementSize) + : segment(nullptr), capTable(nullptr), ptr(nullptr), elementCount(ZERO * ELEMENTS), + step(ZERO * BITS / ELEMENTS), structDataSize(ZERO * BITS), + structPointerCount(ZERO * POINTERS), elementSize(elementSize) {} + + inline word* getLocation() { + // Get the object's location. + + if (elementSize == ElementSize::INLINE_COMPOSITE && ptr != nullptr) { + return reinterpret_cast(ptr) - POINTER_SIZE_IN_WORDS; + } else { + return reinterpret_cast(ptr); + } + } + + inline ElementSize getElementSize() const { return elementSize; } + + inline ListElementCount size() const; + // The number of elements in the list. + + Text::Builder asText(); + Data::Builder asData(); + // Reinterpret the list as a blob. Throws an exception if the elements are not byte-sized. + + template + KJ_ALWAYS_INLINE(T getDataElement(ElementCount index)); + // Get the element of the given type at the given index. + + template + KJ_ALWAYS_INLINE(void setDataElement(ElementCount index, kj::NoInfer value)); + // Set the element at the given index. + + KJ_ALWAYS_INLINE(PointerBuilder getPointerElement(ElementCount index)); + + StructBuilder getStructElement(ElementCount index); + + ListReader asReader() const; + // Get a ListReader pointing at the same memory. + + BuilderArena* getArena(); + // Gets the arena in which this object is allocated. + + CapTableBuilder* getCapTable(); + // Gets the capability context in which this object is operating. + + ListBuilder imbue(CapTableBuilder* capTable); + // Return a copy of this builder except using the given capability context. + +private: + SegmentBuilder* segment; // Memory segment in which the list resides. + CapTableBuilder* capTable; // Table of capability indexes. + + byte* ptr; // Pointer to list content. + + ListElementCount elementCount; // Number of elements in the list. + + BitsPerElementN<23> step; + // The distance between elements. The maximum value occurs when a struct contains 2^16-1 data + // words and 2^16-1 pointers, i.e. 2^17 - 2 words, or 2^23 - 128 bits. + + StructDataBitCount structDataSize; + StructPointerCount structPointerCount; + // The struct properties to use when interpreting the elements as structs. All lists can be + // interpreted as struct lists, so these are always filled in. + + ElementSize elementSize; + // The element size as a ElementSize. This is only really needed to disambiguate INLINE_COMPOSITE + // from other types when the overall size is exactly zero or one words. + + inline ListBuilder(SegmentBuilder* segment, CapTableBuilder* capTable, void* ptr, + BitsPerElementN<23> step, ListElementCount size, + StructDataBitCount structDataSize, StructPointerCount structPointerCount, + ElementSize elementSize) + : segment(segment), capTable(capTable), ptr(reinterpret_cast(ptr)), + elementCount(size), step(step), structDataSize(structDataSize), + structPointerCount(structPointerCount), elementSize(elementSize) {} + + friend class StructBuilder; + friend struct WireHelpers; + friend class OrphanBuilder; +}; + +class ListReader { +public: + inline explicit ListReader(ElementSize elementSize) + : segment(nullptr), capTable(nullptr), ptr(nullptr), elementCount(ZERO * ELEMENTS), + step(ZERO * BITS / ELEMENTS), structDataSize(ZERO * BITS), + structPointerCount(ZERO * POINTERS), elementSize(elementSize), nestingLimit(0x7fffffff) {} + + inline ListElementCount size() const; + // The number of elements in the list. + + inline ElementSize getElementSize() const { return elementSize; } + + Text::Reader asText(); + Data::Reader asData(); + // Reinterpret the list as a blob. Throws an exception if the elements are not byte-sized. + + kj::ArrayPtr asRawBytes(); + + template + KJ_ALWAYS_INLINE(T getDataElement(ElementCount index) const); + // Get the element of the given type at the given index. + + KJ_ALWAYS_INLINE(PointerReader getPointerElement(ElementCount index) const); + + StructReader getStructElement(ElementCount index) const; + + CapTableReader* getCapTable(); + // Gets the capability context in which this object is operating. + + ListReader imbue(CapTableReader* capTable) const; + // Return a copy of this reader except using the given capability context. + + bool isCanonical(const word **readHead, const WirePointer* ref); + // Validate this pointer's canonicity, subject to the conditions: + // * All data to the left of readHead has been read thus far (for pointer + // ordering) + // * All pointers in preorder have already been checked + // * This pointer is in the first and only segment of the message + +private: + SegmentReader* segment; // Memory segment in which the list resides. + CapTableReader* capTable; // Table of capability indexes. + + const byte* ptr; // Pointer to list content. + + ListElementCount elementCount; // Number of elements in the list. + + BitsPerElementN<23> step; + // The distance between elements. The maximum value occurs when a struct contains 2^16-1 data + // words and 2^16-1 pointers, i.e. 2^17 - 2 words, or 2^23 - 2 bits. + + StructDataBitCount structDataSize; + StructPointerCount structPointerCount; + // The struct properties to use when interpreting the elements as structs. All lists can be + // interpreted as struct lists, so these are always filled in. + + ElementSize elementSize; + // The element size as a ElementSize. This is only really needed to disambiguate INLINE_COMPOSITE + // from other types when the overall size is exactly zero or one words. + + int nestingLimit; + // Limits the depth of message structures to guard against stack-overflow-based DoS attacks. + // Once this reaches zero, further pointers will be pruned. + + inline ListReader(SegmentReader* segment, CapTableReader* capTable, const void* ptr, + ListElementCount elementCount, BitsPerElementN<23> step, + StructDataBitCount structDataSize, StructPointerCount structPointerCount, + ElementSize elementSize, int nestingLimit) + : segment(segment), capTable(capTable), ptr(reinterpret_cast(ptr)), + elementCount(elementCount), step(step), structDataSize(structDataSize), + structPointerCount(structPointerCount), elementSize(elementSize), + nestingLimit(nestingLimit) {} + + friend class StructReader; + friend class ListBuilder; + friend struct WireHelpers; + friend class OrphanBuilder; +}; + +// ------------------------------------------------------------------- + +class OrphanBuilder { +public: + inline OrphanBuilder(): segment(nullptr), capTable(nullptr), location(nullptr) { + memset(&tag, 0, sizeof(tag)); + } + OrphanBuilder(const OrphanBuilder& other) = delete; + inline OrphanBuilder(OrphanBuilder&& other) noexcept; + inline ~OrphanBuilder() noexcept(false); + + static OrphanBuilder initStruct(BuilderArena* arena, CapTableBuilder* capTable, StructSize size); + static OrphanBuilder initList(BuilderArena* arena, CapTableBuilder* capTable, + ElementCount elementCount, ElementSize elementSize); + static OrphanBuilder initStructList(BuilderArena* arena, CapTableBuilder* capTable, + ElementCount elementCount, StructSize elementSize); + static OrphanBuilder initText(BuilderArena* arena, CapTableBuilder* capTable, ByteCount size); + static OrphanBuilder initData(BuilderArena* arena, CapTableBuilder* capTable, ByteCount size); + + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, StructReader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, ListReader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, PointerReader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, Text::Reader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, Data::Reader copyFrom); +#if !CAPNP_LITE + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, + kj::Own copyFrom); +#endif // !CAPNP_LITE + + static OrphanBuilder concat(BuilderArena* arena, CapTableBuilder* capTable, + ElementSize expectedElementSize, StructSize expectedStructSize, + kj::ArrayPtr lists); + + static OrphanBuilder referenceExternalData(BuilderArena* arena, Data::Reader data); + + OrphanBuilder& operator=(const OrphanBuilder& other) = delete; + inline OrphanBuilder& operator=(OrphanBuilder&& other); + + inline bool operator==(decltype(nullptr)) const { return location == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return location != nullptr; } + + StructBuilder asStruct(StructSize size); + // Interpret as a struct, or throw an exception if not a struct. + + ListBuilder asList(ElementSize elementSize); + // Interpret as a list, or throw an exception if not a list. elementSize cannot be + // INLINE_COMPOSITE -- use asStructList() instead. + + ListBuilder asStructList(StructSize elementSize); + // Interpret as a struct list, or throw an exception if not a list. + + ListBuilder asListAnySize(); + // For AnyList. + + Text::Builder asText(); + Data::Builder asData(); + // Interpret as a blob, or throw an exception if not a blob. + + StructReader asStructReader(StructSize size) const; + ListReader asListReader(ElementSize elementSize) const; + ListReader asListReaderAnySize() const; +#if !CAPNP_LITE + kj::Own asCapability() const; +#endif // !CAPNP_LITE + Text::Reader asTextReader() const; + Data::Reader asDataReader() const; + + bool truncate(ElementCount size, bool isText) KJ_WARN_UNUSED_RESULT; + // Resize the orphan list to the given size. Returns false if the list is currently empty but + // the requested size is non-zero, in which case the caller will need to allocate a new list. + + void truncate(ElementCount size, ElementSize elementSize); + void truncate(ElementCount size, StructSize elementSize); + void truncateText(ElementCount size); + // Versions of truncate() that know how to allocate a new list if needed. + +private: + static_assert(ONE * POINTERS * WORDS_PER_POINTER == ONE * WORDS, + "This struct assumes a pointer is one word."); + word tag; + // Contains an encoded WirePointer representing this object. WirePointer is defined in + // layout.c++, but fits in a word. + // + // This may be a FAR pointer. Even in that case, `location` points to the eventual destination + // of that far pointer. The reason we keep the far pointer around rather than just making `tag` + // represent the final destination is because if the eventual adopter of the pointer is not in + // the target's segment then it may be useful to reuse the far pointer landing pad. + // + // If `tag` is not a far pointer, its offset is garbage; only `location` points to the actual + // target. + + SegmentBuilder* segment; + // Segment in which the object resides. + + CapTableBuilder* capTable; + // Table of capability indexes. + + word* location; + // Pointer to the object, or nullptr if the pointer is null. For capabilities, we make this + // 0x1 just so that it is non-null for operator==, but it is never used. + + inline OrphanBuilder(const void* tagPtr, SegmentBuilder* segment, + CapTableBuilder* capTable, word* location) + : segment(segment), capTable(capTable), location(location) { + memcpy(&tag, tagPtr, sizeof(tag)); + } + + inline WirePointer* tagAsPtr() { return reinterpret_cast(&tag); } + inline const WirePointer* tagAsPtr() const { return reinterpret_cast(&tag); } + + void euthanize(); + // Erase the target object, zeroing it out and possibly reclaiming the memory. Called when + // the OrphanBuilder is being destroyed or overwritten and it is non-null. + + friend struct WireHelpers; +}; + +// ======================================================================================= +// Internal implementation details... + +// These are defined in the source file. +template <> typename Text::Builder PointerBuilder::initBlob(ByteCount size); +template <> void PointerBuilder::setBlob(typename Text::Reader value); +template <> typename Text::Builder PointerBuilder::getBlob( + const void* defaultValue, ByteCount defaultSize); +template <> typename Text::Reader PointerReader::getBlob( + const void* defaultValue, ByteCount defaultSize) const; + +template <> typename Data::Builder PointerBuilder::initBlob(ByteCount size); +template <> void PointerBuilder::setBlob(typename Data::Reader value); +template <> typename Data::Builder PointerBuilder::getBlob( + const void* defaultValue, ByteCount defaultSize); +template <> typename Data::Reader PointerReader::getBlob( + const void* defaultValue, ByteCount defaultSize) const; + +inline PointerBuilder PointerBuilder::getRoot( + SegmentBuilder* segment, CapTableBuilder* capTable, word* location) { + return PointerBuilder(segment, capTable, reinterpret_cast(location)); +} + +inline PointerReader PointerReader::getRootUnchecked(const word* location) { + return PointerReader(nullptr, nullptr, + reinterpret_cast(location), 0x7fffffff); +} + +// ------------------------------------------------------------------- + +inline kj::ArrayPtr StructBuilder::getDataSectionAsBlob() { + return kj::ArrayPtr(reinterpret_cast(data), + unbound(dataSize / BITS_PER_BYTE / BYTES)); +} + +inline _::ListBuilder StructBuilder::getPointerSectionAsList() { + return _::ListBuilder(segment, capTable, pointers, ONE * POINTERS * BITS_PER_POINTER / ELEMENTS, + pointerCount * (ONE * ELEMENTS / POINTERS), + ZERO * BITS, ONE * POINTERS, ElementSize::POINTER); +} + +template +inline bool StructBuilder::hasDataField(StructDataOffset offset) { + return getDataField>(offset) != 0; +} + +template <> +inline bool StructBuilder::hasDataField(StructDataOffset offset) { + return false; +} + +template +inline T StructBuilder::getDataField(StructDataOffset offset) { + return reinterpret_cast*>(data)[unbound(offset / ELEMENTS)].get(); +} + +template <> +inline bool StructBuilder::getDataField(StructDataOffset offset) { + BitCount32 boffset = offset * (ONE * BITS / ELEMENTS); + byte* b = reinterpret_cast(data) + boffset / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (boffset % BITS_PER_BYTE / BITS))) != 0; +} + +template <> +inline Void StructBuilder::getDataField(StructDataOffset offset) { + return VOID; +} + +template +inline T StructBuilder::getDataField(StructDataOffset offset, Mask mask) { + return unmask(getDataField >(offset), mask); +} + +template +inline void StructBuilder::setDataField(StructDataOffset offset, kj::NoInfer value) { + reinterpret_cast*>(data)[unbound(offset / ELEMENTS)].set(value); +} + +#if CAPNP_CANONICALIZE_NAN +// Use mask() on floats and doubles to make sure we canonicalize NaNs. +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, float value) { + setDataField(offset, mask(value, 0)); +} +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, double value) { + setDataField(offset, mask(value, 0)); +} +#endif + +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, bool value) { + auto boffset = offset * (ONE * BITS / ELEMENTS); + byte* b = reinterpret_cast(data) + boffset / BITS_PER_BYTE; + uint bitnum = unboundMaxBits<3>(boffset % BITS_PER_BYTE / BITS); + *reinterpret_cast(b) = (*reinterpret_cast(b) & ~(1 << bitnum)) + | (static_cast(value) << bitnum); +} + +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, Void value) {} + +template +inline void StructBuilder::setDataField(StructDataOffset offset, + kj::NoInfer value, Mask m) { + setDataField >(offset, mask(value, m)); +} + +inline PointerBuilder StructBuilder::getPointerField(StructPointerOffset ptrIndex) { + // Hacky because WirePointer is defined in the .c++ file (so is incomplete here). + return PointerBuilder(segment, capTable, reinterpret_cast( + reinterpret_cast(pointers) + ptrIndex * WORDS_PER_POINTER)); +} + +// ------------------------------------------------------------------- + +inline kj::ArrayPtr StructReader::getDataSectionAsBlob() { + return kj::ArrayPtr(reinterpret_cast(data), + unbound(dataSize / BITS_PER_BYTE / BYTES)); +} + +inline _::ListReader StructReader::getPointerSectionAsList() { + return _::ListReader(segment, capTable, pointers, pointerCount * (ONE * ELEMENTS / POINTERS), + ONE * POINTERS * BITS_PER_POINTER / ELEMENTS, ZERO * BITS, ONE * POINTERS, + ElementSize::POINTER, nestingLimit); +} + +template +inline bool StructReader::hasDataField(StructDataOffset offset) const { + return getDataField>(offset) != 0; +} + +template <> +inline bool StructReader::hasDataField(StructDataOffset offset) const { + return false; +} + +template +inline T StructReader::getDataField(StructDataOffset offset) const { + if ((offset + ONE * ELEMENTS) * capnp::bitsPerElement() <= dataSize) { + return reinterpret_cast*>(data)[unbound(offset / ELEMENTS)].get(); + } else { + return static_cast(0); + } +} + +template <> +inline bool StructReader::getDataField(StructDataOffset offset) const { + auto boffset = offset * (ONE * BITS / ELEMENTS); + if (boffset < dataSize) { + const byte* b = reinterpret_cast(data) + boffset / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (boffset % BITS_PER_BYTE / BITS))) != 0; + } else { + return false; + } +} + +template <> +inline Void StructReader::getDataField(StructDataOffset offset) const { + return VOID; +} + +template +T StructReader::getDataField(StructDataOffset offset, Mask mask) const { + return unmask(getDataField >(offset), mask); +} + +inline PointerReader StructReader::getPointerField(StructPointerOffset ptrIndex) const { + if (ptrIndex < pointerCount) { + // Hacky because WirePointer is defined in the .c++ file (so is incomplete here). + return PointerReader(segment, capTable, reinterpret_cast( + reinterpret_cast(pointers) + ptrIndex * WORDS_PER_POINTER), nestingLimit); + } else{ + return PointerReader(); + } +} + +// ------------------------------------------------------------------- + +inline ListElementCount ListBuilder::size() const { return elementCount; } + +template +inline T ListBuilder::getDataElement(ElementCount index) { + return reinterpret_cast*>( + ptr + upgradeBound(index) * step / BITS_PER_BYTE)->get(); + + // TODO(perf): Benchmark this alternate implementation, which I suspect may make better use of + // the x86 SIB byte. Also use it for all the other getData/setData implementations below, and + // the various non-inline methods that look up pointers. + // Also if using this, consider changing ptr back to void* instead of byte*. +// return reinterpret_cast*>(ptr)[ +// index / ELEMENTS * (step / capnp::bitsPerElement())].get(); +} + +template <> +inline bool ListBuilder::getDataElement(ElementCount index) { + // Ignore step for bit lists because bit lists cannot be upgraded to struct lists. + auto bindex = index * (ONE * BITS / ELEMENTS); + byte* b = ptr + bindex / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (bindex % BITS_PER_BYTE / BITS))) != 0; +} + +template <> +inline Void ListBuilder::getDataElement(ElementCount index) { + return VOID; +} + +template +inline void ListBuilder::setDataElement(ElementCount index, kj::NoInfer value) { + reinterpret_cast*>( + ptr + upgradeBound(index) * step / BITS_PER_BYTE)->set(value); +} + +#if CAPNP_CANONICALIZE_NAN +// Use mask() on floats and doubles to make sure we canonicalize NaNs. +template <> +inline void ListBuilder::setDataElement(ElementCount index, float value) { + setDataElement(index, mask(value, 0)); +} +template <> +inline void ListBuilder::setDataElement(ElementCount index, double value) { + setDataElement(index, mask(value, 0)); +} +#endif + +template <> +inline void ListBuilder::setDataElement(ElementCount index, bool value) { + // Ignore stepBytes for bit lists because bit lists cannot be upgraded to struct lists. + auto bindex = index * (ONE * BITS / ELEMENTS); + byte* b = ptr + bindex / BITS_PER_BYTE; + auto bitnum = bindex % BITS_PER_BYTE / BITS; + *reinterpret_cast(b) = (*reinterpret_cast(b) & ~(1 << unbound(bitnum))) + | (static_cast(value) << unbound(bitnum)); +} + +template <> +inline void ListBuilder::setDataElement(ElementCount index, Void value) {} + +inline PointerBuilder ListBuilder::getPointerElement(ElementCount index) { + return PointerBuilder(segment, capTable, reinterpret_cast(ptr + + upgradeBound(index) * step / BITS_PER_BYTE)); +} + +// ------------------------------------------------------------------- + +inline ListElementCount ListReader::size() const { return elementCount; } + +template +inline T ListReader::getDataElement(ElementCount index) const { + return reinterpret_cast*>( + ptr + upgradeBound(index) * step / BITS_PER_BYTE)->get(); +} + +template <> +inline bool ListReader::getDataElement(ElementCount index) const { + // Ignore step for bit lists because bit lists cannot be upgraded to struct lists. + auto bindex = index * (ONE * BITS / ELEMENTS); + const byte* b = ptr + bindex / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (bindex % BITS_PER_BYTE / BITS))) != 0; +} + +template <> +inline Void ListReader::getDataElement(ElementCount index) const { + return VOID; +} + +inline PointerReader ListReader::getPointerElement(ElementCount index) const { + return PointerReader(segment, capTable, reinterpret_cast( + ptr + upgradeBound(index) * step / BITS_PER_BYTE), nestingLimit); +} + +// ------------------------------------------------------------------- + +inline OrphanBuilder::OrphanBuilder(OrphanBuilder&& other) noexcept + : segment(other.segment), capTable(other.capTable), location(other.location) { + memcpy(&tag, &other.tag, sizeof(tag)); // Needs memcpy to comply with aliasing rules. + other.segment = nullptr; + other.location = nullptr; +} + +inline OrphanBuilder::~OrphanBuilder() noexcept(false) { + if (segment != nullptr) euthanize(); +} + +inline OrphanBuilder& OrphanBuilder::operator=(OrphanBuilder&& other) { + // With normal smart pointers, it's important to handle the case where the incoming pointer + // is actually transitively owned by this one. In this case, euthanize() would destroy `other` + // before we copied it. This isn't possible in the case of `OrphanBuilder` because it only + // owns message objects, and `other` is not itself a message object, therefore cannot possibly + // be transitively owned by `this`. + + if (segment != nullptr) euthanize(); + segment = other.segment; + capTable = other.capTable; + location = other.location; + memcpy(&tag, &other.tag, sizeof(tag)); // Needs memcpy to comply with aliasing rules. + other.segment = nullptr; + other.location = nullptr; + return *this; +} + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_LAYOUT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/list.h b/phonelibs/capnp-cpp/include/capnp/list.h new file mode 100644 index 00000000000000..23e5e6c10e661f --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/list.h @@ -0,0 +1,546 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_LIST_H_ +#define CAPNP_LIST_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" +#include "orphan.h" +#include +#ifdef KJ_STD_COMPAT +#include +#endif // KJ_STD_COMPAT + +namespace capnp { +namespace _ { // private + +template +class TemporaryPointer { + // This class is a little hack which lets us define operator->() in cases where it needs to + // return a pointer to a temporary value. We instead construct a TemporaryPointer and return that + // (by value). The compiler then invokes operator->() on the TemporaryPointer, which itself is + // able to return a real pointer to its member. + +public: + TemporaryPointer(T&& value): value(kj::mv(value)) {} + TemporaryPointer(const T& value): value(value) {} + + inline T* operator->() { return &value; } +private: + T value; +}; + +template +class IndexingIterator { +public: + IndexingIterator() = default; + + inline Element operator*() const { return (*container)[index]; } + inline TemporaryPointer operator->() const { + return TemporaryPointer((*container)[index]); + } + inline Element operator[]( int off) const { return (*container)[index]; } + inline Element operator[](uint off) const { return (*container)[index]; } + + inline IndexingIterator& operator++() { ++index; return *this; } + inline IndexingIterator operator++(int) { IndexingIterator other = *this; ++index; return other; } + inline IndexingIterator& operator--() { --index; return *this; } + inline IndexingIterator operator--(int) { IndexingIterator other = *this; --index; return other; } + + inline IndexingIterator operator+(uint amount) const { return IndexingIterator(container, index + amount); } + inline IndexingIterator operator-(uint amount) const { return IndexingIterator(container, index - amount); } + inline IndexingIterator operator+( int amount) const { return IndexingIterator(container, index + amount); } + inline IndexingIterator operator-( int amount) const { return IndexingIterator(container, index - amount); } + + inline int operator-(const IndexingIterator& other) const { return index - other.index; } + + inline IndexingIterator& operator+=(uint amount) { index += amount; return *this; } + inline IndexingIterator& operator-=(uint amount) { index -= amount; return *this; } + inline IndexingIterator& operator+=( int amount) { index += amount; return *this; } + inline IndexingIterator& operator-=( int amount) { index -= amount; return *this; } + + // STL says comparing iterators of different containers is not allowed, so we only compare + // indices here. + inline bool operator==(const IndexingIterator& other) const { return index == other.index; } + inline bool operator!=(const IndexingIterator& other) const { return index != other.index; } + inline bool operator<=(const IndexingIterator& other) const { return index <= other.index; } + inline bool operator>=(const IndexingIterator& other) const { return index >= other.index; } + inline bool operator< (const IndexingIterator& other) const { return index < other.index; } + inline bool operator> (const IndexingIterator& other) const { return index > other.index; } + +private: + Container* container; + uint index; + + friend Container; + inline IndexingIterator(Container* container, uint index) + : container(container), index(index) {} +}; + +} // namespace _ (private) + +template +struct List { + // List of primitives. + + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(_::elementSizeForType()) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline T operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return reader.template getDataElement(bounded(index) * ELEMENTS); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + inline Builder(): builder(_::elementSizeForType()) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline T operator[](uint index) { + KJ_IREQUIRE(index < size()); + return builder.template getDataElement(bounded(index) * ELEMENTS); + } + inline void set(uint index, T value) { + // Alas, it is not possible to make operator[] return a reference to which you can assign, + // since the encoded representation does not necessarily match the compiler's representation + // of the type. We can't even return a clever class that implements operator T() and + // operator=() because it will lead to surprising behavior when using type inference (e.g. + // calling a template function with inferred argument types, or using "auto" or "decltype"). + + builder.template setDataElement(bounded(index) * ELEMENTS, value); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(_::elementSizeForType(), bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(_::elementSizeForType(), defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(_::elementSizeForType(), defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +template +struct List: public List {}; + +template +struct List { + // List of structs. + + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(ElementSize::INLINE_COMPOSITE) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename T::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return typename T::Reader(reader.getStructElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + inline Builder(): builder(ElementSize::INLINE_COMPOSITE) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename T::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return typename T::Builder(builder.getStructElement(bounded(index) * ELEMENTS)); + } + + inline void adoptWithCaveats(uint index, Orphan&& orphan) { + // Mostly behaves like you'd expect `adopt` to behave, but with two caveats originating from + // the fact that structs in a struct list are allocated inline rather than by pointer: + // * This actually performs a shallow copy, effectively adopting each of the orphan's + // children rather than adopting the orphan itself. The orphan ends up being discarded, + // possibly wasting space in the message object. + // * If the orphan is larger than the target struct -- say, because the orphan was built + // using a newer version of the schema that has additional fields -- it will be truncated, + // losing data. + + KJ_IREQUIRE(index < size()); + + // We pass a zero-valued StructSize to asStruct() because we do not want the struct to be + // expanded under any circumstances. We're just going to throw it away anyway, and + // transferContentFrom() already carefully compares the struct sizes before transferring. + builder.getStructElement(bounded(index) * ELEMENTS).transferContentFrom( + orphan.builder.asStruct(_::StructSize(ZERO * WORDS, ZERO * POINTERS))); + } + inline void setWithCaveats(uint index, const typename T::Reader& reader) { + // Mostly behaves like you'd expect `set` to behave, but with a caveat originating from + // the fact that structs in a struct list are allocated inline rather than by pointer: + // If the source struct is larger than the target struct -- say, because the source was built + // using a newer version of the schema that has additional fields -- it will be truncated, + // losing data. + // + // Note: If you are trying to concatenate some lists, use Orphanage::newOrphanConcat() to + // do it without losing any data in case the source lists come from a newer version of the + // protocol. (Plus, it's easier to use anyhow.) + + KJ_IREQUIRE(index < size()); + builder.getStructElement(bounded(index) * ELEMENTS).copyContentFrom(reader._reader); + } + + // There are no init(), set(), adopt(), or disown() methods for lists of structs because the + // elements of the list are inlined and are initialized when the list is initialized. This + // means that init() would be redundant, and set() would risk data loss if the input struct + // were from a newer version of the protocol. + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initStructList(bounded(size) * ELEMENTS, _::structSize()); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getStructList(_::structSize(), defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::INLINE_COMPOSITE, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +template +struct List, Kind::LIST> { + // List of lists. + + List() = delete; + + class Reader { + public: + typedef List> Reads; + + inline Reader(): reader(ElementSize::POINTER) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename List::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return typename List::Reader(_::PointerHelpers>::get( + reader.getPointerElement(bounded(index) * ELEMENTS))); + } + + typedef _::IndexingIterator::Reader> Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List> Builds; + + inline Builder(): builder(ElementSize::POINTER) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename List::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return typename List::Builder(_::PointerHelpers>::get( + builder.getPointerElement(bounded(index) * ELEMENTS))); + } + inline typename List::Builder init(uint index, uint size) { + KJ_IREQUIRE(index < this->size()); + return typename List::Builder(_::PointerHelpers>::init( + builder.getPointerElement(bounded(index) * ELEMENTS), size)); + } + inline void set(uint index, typename List::Reader value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).setList(value.reader); + } + void set(uint index, std::initializer_list> value) { + KJ_IREQUIRE(index < size()); + auto l = init(index, value.size()); + uint i = 0; + for (auto& element: value) { + l.set(i++, element); + } + } + inline void adopt(uint index, Orphan&& value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).adopt(kj::mv(value.builder)); + } + inline Orphan disown(uint index) { + KJ_IREQUIRE(index < size()); + return Orphan(builder.getPointerElement(bounded(index) * ELEMENTS).disown()); + } + + typedef _::IndexingIterator::Builder> Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(ElementSize::POINTER, bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(ElementSize::POINTER, defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::POINTER, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +template +struct List { + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(ElementSize::POINTER) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename T::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return reader.getPointerElement(bounded(index) * ELEMENTS) + .template getBlob(nullptr, ZERO * BYTES); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + inline Builder(): builder(ElementSize::POINTER) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename T::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return builder.getPointerElement(bounded(index) * ELEMENTS) + .template getBlob(nullptr, ZERO * BYTES); + } + inline void set(uint index, typename T::Reader value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).template setBlob(value); + } + inline typename T::Builder init(uint index, uint size) { + KJ_IREQUIRE(index < this->size()); + return builder.getPointerElement(bounded(index) * ELEMENTS) + .template initBlob(bounded(size) * BYTES); + } + inline void adopt(uint index, Orphan&& value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).adopt(kj::mv(value.builder)); + } + inline Orphan disown(uint index) { + KJ_IREQUIRE(index < size()); + return Orphan(builder.getPointerElement(bounded(index) * ELEMENTS).disown()); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(ElementSize::POINTER, bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(ElementSize::POINTER, defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::POINTER, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +} // namespace capnp + +#ifdef KJ_STD_COMPAT +namespace std { + +template +struct iterator_traits> + : public std::iterator {}; + +} // namespace std +#endif // KJ_STD_COMPAT + +#endif // CAPNP_LIST_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/membrane.h b/phonelibs/capnp-cpp/include/capnp/membrane.h new file mode 100644 index 00000000000000..6fa8a1335d9418 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/membrane.h @@ -0,0 +1,202 @@ +// Copyright (c) 2015 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_MEMBRANE_H_ +#define CAPNP_MEMBRANE_H_ +// In capability theory, a "membrane" is a wrapper around a capability which (usually) forwards +// calls but recursively wraps capabilities in those calls in the same membrane. The purpose of a +// membrane is to enforce a barrier between two capabilities that cannot be bypassed by merely +// introducing new objects. +// +// The most common use case for a membrane is revocation: Say Alice wants to give Bob a capability +// to access Carol, but wants to be able to revoke this capability later. Alice can accomplish this +// by wrapping Carol in a revokable wrapper which passes through calls until such a time as Alice +// indicates it should be revoked, after which all calls through the wrapper will throw exceptions. +// However, a naive wrapper approach has a problem: if Bob makes a call to Carol and sends a new +// capability in that call, or if Carol returns a capability to Bob in the response to a call, then +// the two are now able to communicate using this new capability, which Alice cannot revoke. In +// order to avoid this problem, Alice must use not just a wrapper but a "membrane", which +// recursively wraps all objects that pass through it in either direction. Thus, all connections +// formed between Bob and Carol (originating from Alice's original introduction) can be revoked +// together by revoking the membrane. +// +// Note that when a capability is passed into a membrane and then passed back out, the result is +// the original capability, not a double-membraned capability. This means that in our revocation +// example, if Bob uses his capability to Carol to obtain another capability from her, then send +// it back to her, the capability Carol receives back will NOT be revoked when Bob's access to +// Carol is revoked. Thus Bob can create long-term irrevocable connections. In most practical use +// cases, this is what you want. APIs commonly rely on the fact that a capability obtained and then +// passed back can be recognized as the original capability. +// +// Mark Miller on membranes: http://www.eros-os.org/pipermail/e-lang/2003-January/008434.html + +#include "capability.h" + +namespace capnp { + +class MembranePolicy { + // Applications may implement this interface to define a membrane policy, which allows some + // calls crossing the membrane to be blocked or redirected. + +public: + virtual kj::Maybe inboundCall( + uint64_t interfaceId, uint16_t methodId, Capability::Client target) = 0; + // Given an inbound call (a call originating "outside" the membrane destined for an object + // "inside" the membrane), decides what to do with it. The policy may: + // + // - Return null to indicate that the call should proceed to the destination. All capabilities + // in the parameters or result will be properly wrapped in the same membrane. + // - Return a capability to have the call redirected to that capability. Note that the redirect + // capability will be treated as outside the membrane, so the params and results will not be + // auto-wrapped; however, the callee can easily wrap the returned capability in the membrane + // itself before returning to achieve this effect. + // - Throw an exception to cause the call to fail with that exception. + // + // `target` is the underlying capability (*inside* the membrane) for which the call is destined. + // Generally, the only way you should use `target` is to wrap it in some capability which you + // return as a redirect. The redirect capability may modify the call in some way and send it to + // `target`. Be careful to use `copyIntoMembrane()` and `copyOutOfMembrane()` as appropriate when + // copying parameters or results across the membrane. + // + // Note that since `target` is inside the capability, if you were to directly return it (rather + // than return null), the effect would be that the membrane would be broken: the call would + // proceed directly and any new capabilities introduced through it would not be membraned. You + // generally should not do that. + + virtual kj::Maybe outboundCall( + uint64_t interfaceId, uint16_t methodId, Capability::Client target) = 0; + // Like `inboundCall()`, but applies to calls originating *inside* the membrane and terminating + // outside. + // + // Note: It is strongly recommended that `outboundCall()` returns null in exactly the same cases + // that `inboundCall()` return null. Conversely, for any case where `inboundCall()` would + // redirect or throw, `outboundCall()` should also redirect or throw. Otherwise, you can run + // into inconsistent behavion when a promise is returned across a membrane, and that promise + // later resolves to a capability on the other side of the membrane: calls on the promise + // will enter and then exit the membrane, but calls on the eventual resolution will not cross + // the membrane at all, so it is important that these two cases behave the same. + + virtual kj::Own addRef() = 0; + // Return a new owned pointer to the same policy. + // + // Typically an implementation of MembranePolicy should also inherit kj::Refcounted and implement + // `addRef()` as `return kj::addRef(*this);`. + // + // Note that the membraning system considers two membranes created with the same MembranePolicy + // object actually to be the *same* membrane. This is relevant when an object passes into the + // membrane and then back out (or out and then back in): instead of double-wrapping the object, + // the wrapping will be removed. +}; + +Capability::Client membrane(Capability::Client inner, kj::Own policy); +// Wrap `inner` in a membrane specified by `policy`. `inner` is considered "inside" the membrane, +// while the returned capability should only be called from outside the membrane. + +Capability::Client reverseMembrane(Capability::Client outer, kj::Own policy); +// Like `membrane` but treat the input capability as "outside" the membrane, and return a +// capability appropriate for use inside. +// +// Applications typically won't use this directly; the membraning code automatically sets up +// reverse membranes where needed. + +template +ClientType membrane(ClientType inner, kj::Own policy); +template +ClientType reverseMembrane(ClientType inner, kj::Own policy); +// Convenience templates which return the same interface type as the input. + +template +typename ServerType::Serves::Client membrane( + kj::Own inner, kj::Own policy); +template +typename ServerType::Serves::Client reverseMembrane( + kj::Own inner, kj::Own policy); +// Convenience templates which input a capability server type and return the appropriate client +// type. + +template +Orphan::Reads> copyIntoMembrane( + Reader&& from, Orphanage to, kj::Own policy); +// Copy a Cap'n Proto object (e.g. struct or list), adding the given membrane to any capabilities +// found within it. `from` is interpreted as "outside" the membrane while `to` is "inside". + +template +Orphan::Reads> copyOutOfMembrane( + Reader&& from, Orphanage to, kj::Own policy); +// Like copyIntoMembrane() except that `from` is "inside" the membrane and `to` is "outside". + +// ======================================================================================= +// inline implementation details + +template +ClientType membrane(ClientType inner, kj::Own policy) { + return membrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} +template +ClientType reverseMembrane(ClientType inner, kj::Own policy) { + return reverseMembrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} + +template +typename ServerType::Serves::Client membrane( + kj::Own inner, kj::Own policy) { + return membrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} +template +typename ServerType::Serves::Client reverseMembrane( + kj::Own inner, kj::Own policy) { + return reverseMembrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} + +namespace _ { // private + +OrphanBuilder copyOutOfMembrane(PointerReader from, Orphanage to, + kj::Own policy, bool reverse); +OrphanBuilder copyOutOfMembrane(StructReader from, Orphanage to, + kj::Own policy, bool reverse); +OrphanBuilder copyOutOfMembrane(ListReader from, Orphanage to, + kj::Own policy, bool reverse); + +} // namespace _ (private) + +template +Orphan::Reads> copyIntoMembrane( + Reader&& from, Orphanage to, kj::Own policy) { + return _::copyOutOfMembrane( + _::PointerHelpers::Reads>::getInternalReader(from), + to, kj::mv(policy), true); +} + +template +Orphan::Reads> copyOutOfMembrane( + Reader&& from, Orphanage to, kj::Own policy) { + return _::copyOutOfMembrane( + _::PointerHelpers::Reads>::getInternalReader(from), + to, kj::mv(policy), false); +} + +} // namespace capnp + +#endif // CAPNP_MEMBRANE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/message.h b/phonelibs/capnp-cpp/include/capnp/message.h new file mode 100644 index 00000000000000..b4d5e9fc82230d --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/message.h @@ -0,0 +1,508 @@ +// Copyright (c) 2013-2016 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#include +#include +#include +#include +#include "common.h" +#include "layout.h" +#include "any.h" + +#ifndef CAPNP_MESSAGE_H_ +#define CAPNP_MESSAGE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +namespace capnp { + +namespace _ { // private + class ReaderArena; + class BuilderArena; +} + +class StructSchema; +class Orphanage; +template +class Orphan; + +// ======================================================================================= + +struct ReaderOptions { + // Options controlling how data is read. + + uint64_t traversalLimitInWords = 8 * 1024 * 1024; + // Limits how many total words of data are allowed to be traversed. Traversal is counted when + // a new struct or list builder is obtained, e.g. from a get() accessor. This means that calling + // the getter for the same sub-struct multiple times will cause it to be double-counted. Once + // the traversal limit is reached, an error will be reported. + // + // This limit exists for security reasons. It is possible for an attacker to construct a message + // in which multiple pointers point at the same location. This is technically invalid, but hard + // to detect. Using such a message, an attacker could cause a message which is small on the wire + // to appear much larger when actually traversed, possibly exhausting server resources leading to + // denial-of-service. + // + // It makes sense to set a traversal limit that is much larger than the underlying message. + // Together with sensible coding practices (e.g. trying to avoid calling sub-object getters + // multiple times, which is expensive anyway), this should provide adequate protection without + // inconvenience. + // + // The default limit is 64 MiB. This may or may not be a sensible number for any given use case, + // but probably at least prevents easy exploitation while also avoiding causing problems in most + // typical cases. + + int nestingLimit = 64; + // Limits how deeply-nested a message structure can be, e.g. structs containing other structs or + // lists of structs. + // + // Like the traversal limit, this limit exists for security reasons. Since it is common to use + // recursive code to traverse recursive data structures, an attacker could easily cause a stack + // overflow by sending a very-deeply-nested (or even cyclic) message, without the message even + // being very large. The default limit of 64 is probably low enough to prevent any chance of + // stack overflow, yet high enough that it is never a problem in practice. +}; + +class MessageReader { + // Abstract interface for an object used to read a Cap'n Proto message. Subclasses of + // MessageReader are responsible for reading the raw, flat message content. Callers should + // usually call `messageReader.getRoot()` to get a `MyStructType::Reader` + // representing the root of the message, then use that to traverse the message content. + // + // Some common subclasses of `MessageReader` include `SegmentArrayMessageReader`, whose + // constructor accepts pointers to the raw data, and `StreamFdMessageReader` (from + // `serialize.h`), which reads the message from a file descriptor. One might implement other + // subclasses to handle things like reading from shared memory segments, mmap()ed files, etc. + +public: + MessageReader(ReaderOptions options); + // It is suggested that subclasses take ReaderOptions as a constructor parameter, but give it a + // default value of "ReaderOptions()". The base class constructor doesn't have a default value + // in order to remind subclasses that they really need to give the user a way to provide this. + + virtual ~MessageReader() noexcept(false); + + virtual kj::ArrayPtr getSegment(uint id) = 0; + // Gets the segment with the given ID, or returns null if no such segment exists. This method + // will be called at most once for each segment ID. + + inline const ReaderOptions& getOptions(); + // Get the options passed to the constructor. + + template + typename RootType::Reader getRoot(); + // Get the root struct of the message, interpreting it as the given struct type. + + template + typename RootType::Reader getRoot(SchemaType schema); + // Dynamically interpret the root struct of the message using the given schema (a StructSchema). + // RootType in this case must be DynamicStruct, and you must #include to + // use this. + + bool isCanonical(); + // Returns whether the message encoded in the reader is in canonical form. + +private: + ReaderOptions options; + + // Space in which we can construct a ReaderArena. We don't use ReaderArena directly here + // because we don't want clients to have to #include arena.h, which itself includes a bunch of + // big STL headers. We don't use a pointer to a ReaderArena because that would require an + // extra malloc on every message which could be expensive when processing small messages. + void* arenaSpace[15 + sizeof(kj::MutexGuarded) / sizeof(void*)]; + bool allocatedArena; + + _::ReaderArena* arena() { return reinterpret_cast<_::ReaderArena*>(arenaSpace); } + AnyPointer::Reader getRootInternal(); +}; + +class MessageBuilder { + // Abstract interface for an object used to allocate and build a message. Subclasses of + // MessageBuilder are responsible for allocating the space in which the message will be written. + // The most common subclass is `MallocMessageBuilder`, but other subclasses may be used to do + // tricky things like allocate messages in shared memory or mmap()ed files. + // + // Creating a new message ususually means allocating a new MessageBuilder (ideally on the stack) + // and then calling `messageBuilder.initRoot()` to get a `MyStructType::Builder`. + // That, in turn, can be used to fill in the message content. When done, you can call + // `messageBuilder.getSegmentsForOutput()` to get a list of flat data arrays containing the + // message. + +public: + MessageBuilder(); + virtual ~MessageBuilder() noexcept(false); + KJ_DISALLOW_COPY(MessageBuilder); + + struct SegmentInit { + kj::ArrayPtr space; + + size_t wordsUsed; + // Number of words in `space` which are used; the rest are free space in which additional + // objects may be allocated. + }; + + explicit MessageBuilder(kj::ArrayPtr segments); + // Create a MessageBuilder backed by existing memory. This is an advanced interface that most + // people should not use. THIS METHOD IS INSECURE; see below. + // + // This allows a MessageBuilder to be constructed to modify an in-memory message without first + // making a copy of the content. This is especially useful in conjunction with mmap(). + // + // The contents of each segment must outlive the MessageBuilder, but the SegmentInit array itself + // only need outlive the constructor. + // + // SECURITY: Do not use this in conjunction with untrusted data. This constructor assumes that + // the input message is valid. This constructor is designed to be used with data you control, + // e.g. an mmap'd file which is owned and accessed by only one program. When reading data you + // do not trust, you *must* load it into a Reader and then copy into a Builder as a means of + // validating the content. + // + // WARNING: It is NOT safe to initialize a MessageBuilder in this way from memory that is + // currently in use by another MessageBuilder or MessageReader. Other readers/builders will + // not observe changes to the segment sizes nor newly-allocated segments caused by allocating + // new objects in this message. + + virtual kj::ArrayPtr allocateSegment(uint minimumSize) = 0; + // Allocates an array of at least the given number of words, throwing an exception or crashing if + // this is not possible. It is expected that this method will usually return more space than + // requested, and the caller should use that extra space as much as possible before allocating + // more. The returned space remains valid at least until the MessageBuilder is destroyed. + // + // Cap'n Proto will only call this once at a time, so the subclass need not worry about + // thread-safety. + + template + typename RootType::Builder initRoot(); + // Initialize the root struct of the message as the given struct type. + + template + void setRoot(Reader&& value); + // Set the root struct to a deep copy of the given struct. + + template + typename RootType::Builder getRoot(); + // Get the root struct of the message, interpreting it as the given struct type. + + template + typename RootType::Builder getRoot(SchemaType schema); + // Dynamically interpret the root struct of the message using the given schema (a StructSchema). + // RootType in this case must be DynamicStruct, and you must #include to + // use this. + + template + typename RootType::Builder initRoot(SchemaType schema); + // Dynamically init the root struct of the message using the given schema (a StructSchema). + // RootType in this case must be DynamicStruct, and you must #include to + // use this. + + template + void adoptRoot(Orphan&& orphan); + // Like setRoot() but adopts the orphan without copying. + + kj::ArrayPtr> getSegmentsForOutput(); + // Get the raw data that makes up the message. + + Orphanage getOrphanage(); + + bool isCanonical(); + // Check whether the message builder is in canonical form + +private: + void* arenaSpace[22]; + // Space in which we can construct a BuilderArena. We don't use BuilderArena directly here + // because we don't want clients to have to #include arena.h, which itself includes a bunch of + // big STL headers. We don't use a pointer to a BuilderArena because that would require an + // extra malloc on every message which could be expensive when processing small messages. + + bool allocatedArena = false; + // We have to initialize the arena lazily because when we do so we want to allocate the root + // pointer immediately, and this will allocate a segment, which requires a virtual function + // call on the MessageBuilder. We can't do such a call in the constructor since the subclass + // isn't constructed yet. This is kind of annoying because it means that getOrphanage() is + // not thread-safe, but that shouldn't be a huge deal... + + _::BuilderArena* arena() { return reinterpret_cast<_::BuilderArena*>(arenaSpace); } + _::SegmentBuilder* getRootSegment(); + AnyPointer::Builder getRootInternal(); +}; + +template +typename RootType::Reader readMessageUnchecked(const word* data); +// IF THE INPUT IS INVALID, THIS MAY CRASH, CORRUPT MEMORY, CREATE A SECURITY HOLE IN YOUR APP, +// MURDER YOUR FIRST-BORN CHILD, AND/OR BRING ABOUT ETERNAL DAMNATION ON ALL OF HUMANITY. DO NOT +// USE UNLESS YOU UNDERSTAND THE CONSEQUENCES. +// +// Given a pointer to a known-valid message located in a single contiguous memory segment, +// returns a reader for that message. No bounds-checking will be done while traversing this +// message. Use this only if you have already verified that all pointers are valid and in-bounds, +// and there are no far pointers in the message. +// +// To create a message that can be passed to this function, build a message using a MallocAllocator +// whose preferred segment size is larger than the message size. This guarantees that the message +// will be allocated as a single segment, meaning getSegmentsForOutput() returns a single word +// array. That word array is your message; you may pass a pointer to its first word into +// readMessageUnchecked() to read the message. +// +// This can be particularly handy for embedding messages in generated code: you can +// embed the raw bytes (using AlignedData) then make a Reader for it using this. This is the way +// default values are embedded in code generated by the Cap'n Proto compiler. E.g., if you have +// a message MyMessage, you can read its default value like so: +// MyMessage::Reader reader = Message::readMessageUnchecked(MyMessage::DEFAULT.words); +// +// To sanitize a message from an untrusted source such that it can be safely passed to +// readMessageUnchecked(), use copyToUnchecked(). + +template +void copyToUnchecked(Reader&& reader, kj::ArrayPtr uncheckedBuffer); +// Copy the content of the given reader into the given buffer, such that it can safely be passed to +// readMessageUnchecked(). The buffer's size must be exactly reader.totalSizeInWords() + 1, +// otherwise an exception will be thrown. The buffer must be zero'd before calling. + +template +typename RootType::Reader readDataStruct(kj::ArrayPtr data); +// Interprets the given data as a single, data-only struct. Only primitive fields (booleans, +// numbers, and enums) will be readable; all pointers will be null. This is useful if you want +// to use Cap'n Proto as a language/platform-neutral way to pack some bits. +// +// The input is a word array rather than a byte array to enforce alignment. If you have a byte +// array which you know is word-aligned (or if your platform supports unaligned reads and you don't +// mind the performance penalty), then you can use `reinterpret_cast` to convert a byte array into +// a word array: +// +// kj::arrayPtr(reinterpret_cast(bytes.begin()), +// reinterpret_cast(bytes.end())) + +template +typename kj::ArrayPtr writeDataStruct(BuilderType builder); +// Given a struct builder, get the underlying data section as a word array, suitable for passing +// to `readDataStruct()`. +// +// Note that you may call `.toBytes()` on the returned value to convert to `ArrayPtr`. + +template +static typename Type::Reader defaultValue(); +// Get a default instance of the given struct or list type. +// +// TODO(cleanup): Find a better home for this function? + +// ======================================================================================= + +class SegmentArrayMessageReader: public MessageReader { + // A simple MessageReader that reads from an array of word arrays representing all segments. + // In particular you can read directly from the output of MessageBuilder::getSegmentsForOutput() + // (although it would probably make more sense to call builder.getRoot().asReader() in that case). + +public: + SegmentArrayMessageReader(kj::ArrayPtr> segments, + ReaderOptions options = ReaderOptions()); + // Creates a message pointing at the given segment array, without taking ownership of the + // segments. All arrays passed in must remain valid until the MessageReader is destroyed. + + KJ_DISALLOW_COPY(SegmentArrayMessageReader); + ~SegmentArrayMessageReader() noexcept(false); + + virtual kj::ArrayPtr getSegment(uint id) override; + +private: + kj::ArrayPtr> segments; +}; + +enum class AllocationStrategy: uint8_t { + FIXED_SIZE, + // The builder will prefer to allocate the same amount of space for each segment with no + // heuristic growth. It will still allocate larger segments when the preferred size is too small + // for some single object. This mode is generally not recommended, but can be particularly useful + // for testing in order to force a message to allocate a predictable number of segments. Note + // that you can force every single object in the message to be located in a separate segment by + // using this mode with firstSegmentWords = 0. + + GROW_HEURISTICALLY + // The builder will heuristically decide how much space to allocate for each segment. Each + // allocated segment will be progressively larger than the previous segments on the assumption + // that message sizes are exponentially distributed. The total number of segments that will be + // allocated for a message of size n is O(log n). +}; + +constexpr uint SUGGESTED_FIRST_SEGMENT_WORDS = 1024; +constexpr AllocationStrategy SUGGESTED_ALLOCATION_STRATEGY = AllocationStrategy::GROW_HEURISTICALLY; + +class MallocMessageBuilder: public MessageBuilder { + // A simple MessageBuilder that uses malloc() (actually, calloc()) to allocate segments. This + // implementation should be reasonable for any case that doesn't require writing the message to + // a specific location in memory. + +public: + explicit MallocMessageBuilder(uint firstSegmentWords = SUGGESTED_FIRST_SEGMENT_WORDS, + AllocationStrategy allocationStrategy = SUGGESTED_ALLOCATION_STRATEGY); + // Creates a BuilderContext which allocates at least the given number of words for the first + // segment, and then uses the given strategy to decide how much to allocate for subsequent + // segments. When choosing a value for firstSegmentWords, consider that: + // 1) Reading and writing messages gets slower when multiple segments are involved, so it's good + // if most messages fit in a single segment. + // 2) Unused bytes will not be written to the wire, so generally it is not a big deal to allocate + // more space than you need. It only becomes problematic if you are allocating many messages + // in parallel and thus use lots of memory, or if you allocate so much extra space that just + // zeroing it out becomes a bottleneck. + // The defaults have been chosen to be reasonable for most people, so don't change them unless you + // have reason to believe you need to. + + explicit MallocMessageBuilder(kj::ArrayPtr firstSegment, + AllocationStrategy allocationStrategy = SUGGESTED_ALLOCATION_STRATEGY); + // This version always returns the given array for the first segment, and then proceeds with the + // allocation strategy. This is useful for optimization when building lots of small messages in + // a tight loop: you can reuse the space for the first segment. + // + // firstSegment MUST be zero-initialized. MallocMessageBuilder's destructor will write new zeros + // over any space that was used so that it can be reused. + + KJ_DISALLOW_COPY(MallocMessageBuilder); + virtual ~MallocMessageBuilder() noexcept(false); + + virtual kj::ArrayPtr allocateSegment(uint minimumSize) override; + +private: + uint nextSize; + AllocationStrategy allocationStrategy; + + bool ownFirstSegment; + bool returnedFirstSegment; + + void* firstSegment; + + struct MoreSegments; + kj::Maybe> moreSegments; +}; + +class FlatMessageBuilder: public MessageBuilder { + // THIS IS NOT THE CLASS YOU'RE LOOKING FOR. + // + // If you want to write a message into already-existing scratch space, use `MallocMessageBuilder` + // and pass the scratch space to its constructor. It will then only fall back to malloc() if + // the scratch space is not large enough. + // + // Do NOT use this class unless you really know what you're doing. This class is problematic + // because it requires advance knowledge of the size of your message, which is usually impossible + // to determine without actually building the message. The class was created primarily to + // implement `copyToUnchecked()`, which itself exists only to support other internal parts of + // the Cap'n Proto implementation. + +public: + explicit FlatMessageBuilder(kj::ArrayPtr array); + KJ_DISALLOW_COPY(FlatMessageBuilder); + virtual ~FlatMessageBuilder() noexcept(false); + + void requireFilled(); + // Throws an exception if the flat array is not exactly full. + + virtual kj::ArrayPtr allocateSegment(uint minimumSize) override; + +private: + kj::ArrayPtr array; + bool allocated; +}; + +// ======================================================================================= +// implementation details + +inline const ReaderOptions& MessageReader::getOptions() { + return options; +} + +template +inline typename RootType::Reader MessageReader::getRoot() { + return getRootInternal().getAs(); +} + +template +inline typename RootType::Builder MessageBuilder::initRoot() { + return getRootInternal().initAs(); +} + +template +inline void MessageBuilder::setRoot(Reader&& value) { + getRootInternal().setAs>(value); +} + +template +inline typename RootType::Builder MessageBuilder::getRoot() { + return getRootInternal().getAs(); +} + +template +void MessageBuilder::adoptRoot(Orphan&& orphan) { + return getRootInternal().adopt(kj::mv(orphan)); +} + +template +typename RootType::Reader MessageReader::getRoot(SchemaType schema) { + return getRootInternal().getAs(schema); +} + +template +typename RootType::Builder MessageBuilder::getRoot(SchemaType schema) { + return getRootInternal().getAs(schema); +} + +template +typename RootType::Builder MessageBuilder::initRoot(SchemaType schema) { + return getRootInternal().initAs(schema); +} + +template +typename RootType::Reader readMessageUnchecked(const word* data) { + return AnyPointer::Reader(_::PointerReader::getRootUnchecked(data)).getAs(); +} + +template +void copyToUnchecked(Reader&& reader, kj::ArrayPtr uncheckedBuffer) { + FlatMessageBuilder builder(uncheckedBuffer); + builder.setRoot(kj::fwd(reader)); + builder.requireFilled(); +} + +template +typename RootType::Reader readDataStruct(kj::ArrayPtr data) { + return typename RootType::Reader(_::StructReader(data)); +} + +template +typename kj::ArrayPtr writeDataStruct(BuilderType builder) { + auto bytes = _::PointerHelpers>::getInternalBuilder(kj::mv(builder)) + .getDataSectionAsBlob(); + return kj::arrayPtr(reinterpret_cast(bytes.begin()), + reinterpret_cast(bytes.end())); +} + +template +static typename Type::Reader defaultValue() { + return typename Type::Reader(_::StructReader()); +} + +template +kj::Array canonicalize(T&& reader) { + return _::PointerHelpers>::getInternalReader(reader).canonicalize(); +} + +} // namespace capnp + +#endif // CAPNP_MESSAGE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/orphan.h b/phonelibs/capnp-cpp/include/capnp/orphan.h new file mode 100644 index 00000000000000..8c8b9a6054c885 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/orphan.h @@ -0,0 +1,440 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_ORPHAN_H_ +#define CAPNP_ORPHAN_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" + +namespace capnp { + +class StructSchema; +class ListSchema; +struct DynamicStruct; +struct DynamicList; +namespace _ { struct OrphanageInternal; } + +template +class Orphan { + // Represents an object which is allocated within some message builder but has no pointers + // pointing at it. An Orphan can later be "adopted" by some other object as one of that object's + // fields, without having to copy the orphan. For a field `foo` of pointer type, the generated + // code will define builder methods `void adoptFoo(Orphan)` and `Orphan disownFoo()`. + // Orphans can also be created independently of any parent using an Orphanage. + // + // `Orphan` can be moved but not copied, like `Own`, so that it is impossible for one + // orphan to be adopted multiple times. If an orphan is destroyed without being adopted, its + // contents are zero'd out (and possibly reused, if we ever implement the ability to reuse space + // in a message arena). + +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + inline Orphan(_::OrphanBuilder&& builder): builder(kj::mv(builder)) {} + + inline BuilderFor get(); + // Get the underlying builder. If the orphan is null, this will allocate and return a default + // object rather than crash. This is done for security -- otherwise, you might enable a DoS + // attack any time you disown a field and fail to check if it is null. In the case of structs, + // this means that the orphan is no longer null after get() returns. In the case of lists, + // no actual object is allocated since a simple empty ListBuilder can be returned. + + inline ReaderFor getReader() const; + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + + inline void truncate(uint size); + // Resize an object (which must be a list or a blob) to the given size. + // + // If the new size is less than the original, the remaining elements will be discarded. The + // list is never moved in this case. If the list happens to be located at the end of its segment + // (which is always true if the list was the last thing allocated), the removed memory will be + // reclaimed (reducing the messag size), otherwise it is simply zeroed. The reclaiming behavior + // is particularly useful for allocating buffer space when you aren't sure how much space you + // actually need: you can pre-allocate, say, a 4k byte array, read() from a file into it, and + // then truncate it back to the amount of space actually used. + // + // If the new size is greater than the original, the list is extended with default values. If + // the list is the last object in its segment *and* there is enough space left in the segment to + // extend it to cover the new values, then the list is extended in-place. Otherwise, it must be + // moved to a new location, leaving a zero'd hole in the previous space that won't be filled. + // This copy is shallow; sub-objects will simply be reparented, not copied. + // + // Any existing readers or builders pointing at the object are invalidated by this call (even if + // it doesn't move). You must call `get()` or `getReader()` again to get the new, valid pointer. + +private: + _::OrphanBuilder builder; + + template + friend struct _::PointerHelpers; + template + friend struct List; + template + friend class Orphan; + friend class Orphanage; + friend class MessageBuilder; +}; + +class Orphanage: private kj::DisallowConstCopy { + // Use to directly allocate Orphan objects, without having a parent object allocate and then + // disown the object. + +public: + inline Orphanage(): arena(nullptr) {} + + template + static Orphanage getForMessageContaining(BuilderType builder); + // Construct an Orphanage that allocates within the message containing the given Builder. This + // allows the constructed Orphans to be adopted by objects within said message. + // + // This constructor takes the builder rather than having the builder have a getOrphanage() method + // because this is an advanced feature and we don't want to pollute the builder APIs with it. + // + // Note that if you have a direct pointer to the `MessageBuilder`, you can simply call its + // `getOrphanage()` method. + + template + Orphan newOrphan() const; + // Allocate a new orphaned struct. + + template + Orphan newOrphan(uint size) const; + // Allocate a new orphaned list or blob. + + Orphan newOrphan(StructSchema schema) const; + // Dynamically create an orphan struct with the given schema. You must + // #include to use this. + + Orphan newOrphan(ListSchema schema, uint size) const; + // Dynamically create an orphan list with the given schema. You must #include + // to use this. + + template + Orphan> newOrphanCopy(Reader copyFrom) const; + // Allocate a new orphaned object (struct, list, or blob) and initialize it as a copy of the + // given object. + + template + Orphan>>> newOrphanConcat(kj::ArrayPtr lists) const; + template + Orphan>>> newOrphanConcat(kj::ArrayPtr lists) const; + // Given an array of List readers, copy and concatenate the lists, creating a new Orphan. + // + // Note that compared to allocating the list yourself and using `setWithCaveats()` to set each + // item, this method avoids the "caveats": the new list will be allocated with the element size + // being the maximum of that from all the input lists. This is particularly important when + // concatenating struct lists: if the lists were created using a newer version of the protocol + // in which some new fields had been added to the struct, using `setWithCaveats()` would + // truncate off those new fields. + + Orphan referenceExternalData(Data::Reader data) const; + // Creates an Orphan that points at an existing region of memory (e.g. from another message) + // without copying it. There are some SEVERE restrictions on how this can be used: + // - The memory must remain valid until the `MessageBuilder` is destroyed (even if the orphan is + // abandoned). + // - Because the data is const, you will not be allowed to obtain a `Data::Builder` + // for this blob. Any call which would return such a builder will throw an exception. You + // can, however, obtain a Reader, e.g. via orphan.getReader() or from a parent Reader (once + // the orphan is adopted). It is your responsibility to make sure your code can deal with + // these problems when using this optimization; if you can't, allocate a copy instead. + // - `data.begin()` must be aligned to a machine word boundary (32-bit or 64-bit depending on + // the CPU). Any pointer returned by malloc() as well as any data blob obtained from another + // Cap'n Proto message satisfies this. + // - If `data.size()` is not a multiple of 8, extra bytes past data.end() up until the next 8-byte + // boundary will be visible in the raw message when it is written out. Thus, there must be no + // secrets in these bytes. Data blobs obtained from other Cap'n Proto messages should be safe + // as these bytes should be zero (unless the sender had the same problem). + // + // The array will actually become one of the message's segments. The data can thus be adopted + // into the message tree without copying it. This is particularly useful when referencing very + // large blobs, such as whole mmap'd files. + +private: + _::BuilderArena* arena; + _::CapTableBuilder* capTable; + + inline explicit Orphanage(_::BuilderArena* arena, _::CapTableBuilder* capTable) + : arena(arena), capTable(capTable) {} + + template + struct GetInnerBuilder; + template + struct GetInnerReader; + template + struct NewOrphanListImpl; + + friend class MessageBuilder; + friend struct _::OrphanageInternal; +}; + +// ======================================================================================= +// Inline implementation details. + +namespace _ { // private + +template +struct OrphanGetImpl; + +template +struct OrphanGetImpl { + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, _::elementSizeForType()); + } +}; + +template +struct OrphanGetImpl { + static inline typename T::Builder apply(_::OrphanBuilder& builder) { + return typename T::Builder(builder.asStruct(_::structSize())); + } + static inline typename T::Reader applyReader(const _::OrphanBuilder& builder) { + return typename T::Reader(builder.asStructReader(_::structSize())); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, _::structSize()); + } +}; + +#if !CAPNP_LITE +template +struct OrphanGetImpl { + static inline typename T::Client apply(_::OrphanBuilder& builder) { + return typename T::Client(builder.asCapability()); + } + static inline typename T::Client applyReader(const _::OrphanBuilder& builder) { + return typename T::Client(builder.asCapability()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; +#endif // !CAPNP_LITE + +template +struct OrphanGetImpl, Kind::LIST> { + static inline typename List::Builder apply(_::OrphanBuilder& builder) { + return typename List::Builder(builder.asList(_::ElementSizeForType::value)); + } + static inline typename List::Reader applyReader(const _::OrphanBuilder& builder) { + return typename List::Reader(builder.asListReader(_::ElementSizeForType::value)); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +template +struct OrphanGetImpl, Kind::LIST> { + static inline typename List::Builder apply(_::OrphanBuilder& builder) { + return typename List::Builder(builder.asStructList(_::structSize())); + } + static inline typename List::Reader applyReader(const _::OrphanBuilder& builder) { + return typename List::Reader(builder.asListReader(_::ElementSizeForType::value)); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +template <> +struct OrphanGetImpl { + static inline Text::Builder apply(_::OrphanBuilder& builder) { + return Text::Builder(builder.asText()); + } + static inline Text::Reader applyReader(const _::OrphanBuilder& builder) { + return Text::Reader(builder.asTextReader()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +template <> +struct OrphanGetImpl { + static inline Data::Builder apply(_::OrphanBuilder& builder) { + return Data::Builder(builder.asData()); + } + static inline Data::Reader applyReader(const _::OrphanBuilder& builder) { + return Data::Reader(builder.asDataReader()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +struct OrphanageInternal { + static inline _::BuilderArena* getArena(Orphanage orphanage) { return orphanage.arena; } + static inline _::CapTableBuilder* getCapTable(Orphanage orphanage) { return orphanage.capTable; } +}; + +} // namespace _ (private) + +template +inline BuilderFor Orphan::get() { + return _::OrphanGetImpl::apply(builder); +} + +template +inline ReaderFor Orphan::getReader() const { + return _::OrphanGetImpl::applyReader(builder); +} + +template +inline void Orphan::truncate(uint size) { + _::OrphanGetImpl>::truncateListOf(builder, bounded(size) * ELEMENTS); +} + +template <> +inline void Orphan::truncate(uint size) { + builder.truncateText(bounded(size) * ELEMENTS); +} + +template <> +inline void Orphan::truncate(uint size) { + builder.truncate(bounded(size) * ELEMENTS, ElementSize::BYTE); +} + +template +struct Orphanage::GetInnerBuilder { + static inline _::StructBuilder apply(typename T::Builder& t) { + return t._builder; + } +}; + +template +struct Orphanage::GetInnerBuilder { + static inline _::ListBuilder apply(typename T::Builder& t) { + return t.builder; + } +}; + +template +Orphanage Orphanage::getForMessageContaining(BuilderType builder) { + auto inner = GetInnerBuilder>::apply(builder); + return Orphanage(inner.getArena(), inner.getCapTable()); +} + +template +Orphan Orphanage::newOrphan() const { + return Orphan(_::OrphanBuilder::initStruct(arena, capTable, _::structSize())); +} + +template +struct Orphanage::NewOrphanListImpl> { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initList( + arena, capTable, bounded(size) * ELEMENTS, _::ElementSizeForType::value); + } +}; + +template +struct Orphanage::NewOrphanListImpl> { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initStructList( + arena, capTable, bounded(size) * ELEMENTS, _::structSize()); + } +}; + +template <> +struct Orphanage::NewOrphanListImpl { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initText(arena, capTable, bounded(size) * BYTES); + } +}; + +template <> +struct Orphanage::NewOrphanListImpl { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initData(arena, capTable, bounded(size) * BYTES); + } +}; + +template +Orphan Orphanage::newOrphan(uint size) const { + return Orphan(NewOrphanListImpl::apply(arena, capTable, size)); +} + +template +struct Orphanage::GetInnerReader { + static inline _::StructReader apply(const typename T::Reader& t) { + return t._reader; + } +}; + +template +struct Orphanage::GetInnerReader { + static inline _::ListReader apply(const typename T::Reader& t) { + return t.reader; + } +}; + +template +struct Orphanage::GetInnerReader { + static inline const typename T::Reader& apply(const typename T::Reader& t) { + return t; + } +}; + +template +inline Orphan> Orphanage::newOrphanCopy(Reader copyFrom) const { + return Orphan>(_::OrphanBuilder::copy( + arena, capTable, GetInnerReader>::apply(copyFrom))); +} + +template +inline Orphan>>> +Orphanage::newOrphanConcat(kj::ArrayPtr lists) const { + return newOrphanConcat(kj::implicitCast>(lists)); +} +template +inline Orphan>>> +Orphanage::newOrphanConcat(kj::ArrayPtr lists) const { + // Optimization / simplification: Rely on List::Reader containing nothing except a + // _::ListReader. + static_assert(sizeof(T) == sizeof(_::ListReader), "lists are not bare readers?"); + kj::ArrayPtr raw( + reinterpret_cast(lists.begin()), lists.size()); + typedef ListElementType> Element; + return Orphan>( + _::OrphanBuilder::concat(arena, capTable, + _::elementSizeForType(), + _::minStructSizeForElement(), raw)); +} + +inline Orphan Orphanage::referenceExternalData(Data::Reader data) const { + return Orphan(_::OrphanBuilder::referenceExternalData(arena, data)); +} + +} // namespace capnp + +#endif // CAPNP_ORPHAN_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/persistent.capnp b/phonelibs/capnp-cpp/include/capnp/persistent.capnp new file mode 100644 index 00000000000000..a13b47168a4cc8 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/persistent.capnp @@ -0,0 +1,139 @@ +# Copyright (c) 2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xb8630836983feed7; + +$import "/capnp/c++.capnp".namespace("capnp"); + +interface Persistent@0xc8cb212fcd9f5691(SturdyRef, Owner) { + # Interface implemented by capabilities that outlive a single connection. A client may save() + # the capability, producing a SturdyRef. The SturdyRef can be stored to disk, then later used to + # obtain a new reference to the capability on a future connection. + # + # The exact format of SturdyRef depends on the "realm" in which the SturdyRef appears. A "realm" + # is an abstract space in which all SturdyRefs have the same format and refer to the same set of + # resources. Every vat is in exactly one realm. All capability clients within that vat must + # produce SturdyRefs of the format appropriate for the realm. + # + # Similarly, every VatNetwork also resides in a particular realm. Usually, a vat's "realm" + # corresponds to the realm of its main VatNetwork. However, a Vat can in fact communicate over + # a VatNetwork in a different realm -- in this case, all SturdyRefs need to be transformed when + # coming or going through said VatNetwork. The RPC system has hooks for registering + # transformation callbacks for this purpose. + # + # Since the format of SturdyRef is realm-dependent, it is not defined here. An application should + # choose an appropriate realm for itself as part of its design. Note that under Sandstorm, every + # application exists in its own realm and is therefore free to define its own SturdyRef format; + # the Sandstorm platform handles translating between realms. + # + # Note that whether a capability is persistent is often orthogonal to its type. In these cases, + # the capability's interface should NOT inherit `Persistent`; instead, just perform a cast at + # runtime. It's not type-safe, but trying to be type-safe in these cases will likely lead to + # tears. In cases where a particular interface only makes sense on persistent capabilities, it + # still should not explicitly inherit Persistent because the `SturdyRef` and `Owner` types will + # vary between realms (they may even be different at the call site than they are on the + # implementation). Instead, mark persistent interfaces with the $persistent annotation (defined + # below). + # + # Sealing + # ------- + # + # As an added security measure, SturdyRefs may be "sealed" to a particular owner, such that + # if the SturdyRef itself leaks to a third party, that party cannot actually restore it because + # they are not the owner. To restore a sealed capability, you must first prove to its host that + # you are the rightful owner. The precise mechanism for this authentication is defined by the + # realm. + # + # Sealing is a defense-in-depth mechanism meant to mitigate damage in the case of catastrophic + # attacks. For example, say an attacker temporarily gains read access to a database full of + # SturdyRefs: it would be unfortunate if it were then necessary to revoke every single reference + # in the database to prevent the attacker from using them. + # + # In general, an "owner" is a course-grained identity. Because capability-based security is still + # the primary mechanism of security, it is not necessary nor desirable to have a separate "owner" + # identity for every single process or object; that is exactly what capabilities are supposed to + # avoid! Instead, it makes sense for an "owner" to literally identify the owner of the machines + # where the capability is stored. If untrusted third parties are able to run arbitrary code on + # said machines, then the sandbox for that code should be designed using Distributed Confinement + # such that the third-party code never sees the bits of the SturdyRefs and cannot directly + # exercise the owner's power to restore refs. See: + # + # http://www.erights.org/elib/capability/dist-confine.html + # + # Resist the urge to represent an Owner as a simple public key. The whole point of sealing is to + # defend against leaked-storage attacks. Such attacks can easily result in the owner's private + # key being stolen as well. A better solution is for `Owner` to contain a simple globally unique + # identifier for the owner, and for everyone to separately maintain a mapping of owner IDs to + # public keys. If an owner's private key is compromised, then humans will need to communicate + # and agree on a replacement public key, then update the mapping. + # + # As a concrete example, an `Owner` could simply contain a domain name, and restoring a SturdyRef + # would require signing a request using the domain's private key. Authenticating this key could + # be accomplished through certificate authorities or web-of-trust techniques. + + save @0 SaveParams -> SaveResults; + # Save a capability persistently so that it can be restored by a future connection. Not all + # capabilities can be saved -- application interfaces should define which capabilities support + # this and which do not. + + struct SaveParams { + sealFor @0 :Owner; + # Seal the SturdyRef so that it can only be restored by the specified Owner. This is meant + # to mitigate damage when a SturdyRef is leaked. See comments above. + # + # Leaving this value null may or may not be allowed; it is up to the realm to decide. If a + # realm does allow a null owner, this should indicate that anyone is allowed to restore the + # ref. + } + struct SaveResults { + sturdyRef @0 :SturdyRef; + } +} + +interface RealmGateway(InternalRef, ExternalRef, InternalOwner, ExternalOwner) { + # Interface invoked when a SturdyRef is about to cross realms. The RPC system supports providing + # a RealmGateway as a callback hook when setting up RPC over some VatNetwork. + + import @0 (cap :Persistent(ExternalRef, ExternalOwner), + params :Persistent(InternalRef, InternalOwner).SaveParams) + -> Persistent(InternalRef, InternalOwner).SaveResults; + # Given an external capability, save it and return an internal reference. Used when someone + # inside the realm tries to save a capability from outside the realm. + + export @1 (cap :Persistent(InternalRef, InternalOwner), + params :Persistent(ExternalRef, ExternalOwner).SaveParams) + -> Persistent(ExternalRef, ExternalOwner).SaveResults; + # Given an internal capability, save it and return an external reference. Used when someone + # outside the realm tries to save a capability from inside the realm. +} + +annotation persistent(interface, field) :Void; +# Apply this annotation to interfaces for objects that will always be persistent, instead of +# extending the Persistent capability, since the correct type parameters to Persistent depend on +# the realm, which is orthogonal to the interface type and therefore should not be defined +# along-side it. +# +# You may also apply this annotation to a capability-typed field which will always contain a +# persistent capability, but where the capability's interface itself is not already marked +# persistent. +# +# Note that absence of the $persistent annotation doesn't mean a capability of that type isn't +# persistent; it just means not *all* such capabilities are persistent. diff --git a/phonelibs/capnp-cpp/include/capnp/persistent.capnp.h b/phonelibs/capnp-cpp/include/capnp/persistent.capnp.h new file mode 100644 index 00000000000000..f9b443220a9584 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/persistent.capnp.h @@ -0,0 +1,1328 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: persistent.capnp + +#ifndef CAPNP_INCLUDED_b8630836983feed7_ +#define CAPNP_INCLUDED_b8630836983feed7_ + +#include +#if !CAPNP_LITE +#include +#endif // !CAPNP_LITE + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(c8cb212fcd9f5691); +CAPNP_DECLARE_SCHEMA(f76fba59183073a5); +CAPNP_DECLARE_SCHEMA(b76848c18c40efbf); +CAPNP_DECLARE_SCHEMA(84ff286cd00a3ed4); +CAPNP_DECLARE_SCHEMA(f0c2cc1d3909574d); +CAPNP_DECLARE_SCHEMA(ecafa18b482da3aa); +CAPNP_DECLARE_SCHEMA(f622595091cafb67); + +} // namespace schemas +} // namespace capnp + +namespace capnp { + +template +struct Persistent { + Persistent() = delete; + +#if !CAPNP_LITE + class Client; + class Server; +#endif // !CAPNP_LITE + + struct SaveParams; + struct SaveResults; + + #if !CAPNP_LITE + struct _capnpPrivate { + CAPNP_DECLARE_INTERFACE_HEADER(c8cb212fcd9f5691) + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, SturdyRef, Owner>::brand(); } + }; + #endif // !CAPNP_LITE +}; + +template +struct Persistent::SaveParams { + SaveParams() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f76fba59183073a5, 0, 1) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, SturdyRef, Owner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +template +struct Persistent::SaveResults { + SaveResults() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b76848c18c40efbf, 0, 1) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, SturdyRef, Owner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +template +struct RealmGateway { + RealmGateway() = delete; + +#if !CAPNP_LITE + class Client; + class Server; +#endif // !CAPNP_LITE + + struct ImportParams; + struct ExportParams; + + #if !CAPNP_LITE + struct _capnpPrivate { + CAPNP_DECLARE_INTERFACE_HEADER(84ff286cd00a3ed4) + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, InternalRef, ExternalRef, InternalOwner, ExternalOwner>::brand(); } + }; + #endif // !CAPNP_LITE +}; + +template +struct RealmGateway::ImportParams { + ImportParams() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f0c2cc1d3909574d, 0, 2) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, InternalRef, ExternalRef, InternalOwner, ExternalOwner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +template +struct RealmGateway::ExportParams { + ExportParams() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ecafa18b482da3aa, 0, 2) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, InternalRef, ExternalRef, InternalOwner, ExternalOwner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +#if !CAPNP_LITE +template +class Persistent::Client + : public virtual ::capnp::Capability::Client { +public: + typedef Persistent Calls; + typedef Persistent Reads; + + Client(decltype(nullptr)); + explicit Client(::kj::Own< ::capnp::ClientHook>&& hook); + template ()>> + Client(::kj::Own<_t>&& server); + template ()>> + Client(::kj::Promise<_t>&& promise); + Client(::kj::Exception&& exception); + Client(Client&) = default; + Client(Client&&) = default; + Client& operator=(Client& other); + Client& operator=(Client&& other); + + template + typename Persistent::Client asGeneric() { + return castAs>(); + } + + CAPNP_AUTO_IF_MSVC(::capnp::Request::SaveParams, typename ::capnp::Persistent::SaveResults>) saveRequest( + ::kj::Maybe< ::capnp::MessageSize> sizeHint = nullptr); + +protected: + Client() = default; +}; + +template +class Persistent::Server + : public virtual ::capnp::Capability::Server { +public: + typedef Persistent Serves; + + ::kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) + override; + +protected: + typedef ::capnp::CallContext::SaveParams, typename ::capnp::Persistent::SaveResults> SaveContext; + virtual ::kj::Promise save(SaveContext context); + + inline typename ::capnp::Persistent::Client thisCap() { + return ::capnp::Capability::Server::thisCap() + .template castAs< ::capnp::Persistent>(); + } + + ::kj::Promise dispatchCallInternal(uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context); +}; +#endif // !CAPNP_LITE + +template +class Persistent::SaveParams::Reader { +public: + typedef SaveParams Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveParams::Reader asPersistentGeneric() { + return typename Persistent::SaveParams::Reader(_reader); + } + + inline bool hasSealFor() const; + inline ::capnp::ReaderFor getSealFor() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class Persistent::SaveParams::Builder { +public: + typedef SaveParams Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveParams::Builder asPersistentGeneric() { + return typename Persistent::SaveParams::Builder(_builder); + } + + inline bool hasSealFor(); + inline ::capnp::BuilderFor getSealFor(); + inline void setSealFor( ::capnp::ReaderFor value); + inline ::capnp::BuilderFor initSealFor(); + inline ::capnp::BuilderFor initSealFor(unsigned int size); + inline void adoptSealFor(::capnp::Orphan&& value); + inline ::capnp::Orphan disownSealFor(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class Persistent::SaveParams::Pipeline { +public: + typedef SaveParams Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::PipelineFor getSealFor(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +template +class Persistent::SaveResults::Reader { +public: + typedef SaveResults Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveResults::Reader asPersistentGeneric() { + return typename Persistent::SaveResults::Reader(_reader); + } + + inline bool hasSturdyRef() const; + inline ::capnp::ReaderFor getSturdyRef() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class Persistent::SaveResults::Builder { +public: + typedef SaveResults Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveResults::Builder asPersistentGeneric() { + return typename Persistent::SaveResults::Builder(_builder); + } + + inline bool hasSturdyRef(); + inline ::capnp::BuilderFor getSturdyRef(); + inline void setSturdyRef( ::capnp::ReaderFor value); + inline ::capnp::BuilderFor initSturdyRef(); + inline ::capnp::BuilderFor initSturdyRef(unsigned int size); + inline void adoptSturdyRef(::capnp::Orphan&& value); + inline ::capnp::Orphan disownSturdyRef(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class Persistent::SaveResults::Pipeline { +public: + typedef SaveResults Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::PipelineFor getSturdyRef(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +class RealmGateway::Client + : public virtual ::capnp::Capability::Client { +public: + typedef RealmGateway Calls; + typedef RealmGateway Reads; + + Client(decltype(nullptr)); + explicit Client(::kj::Own< ::capnp::ClientHook>&& hook); + template ()>> + Client(::kj::Own<_t>&& server); + template ()>> + Client(::kj::Promise<_t>&& promise); + Client(::kj::Exception&& exception); + Client(Client&) = default; + Client(Client&&) = default; + Client& operator=(Client& other); + Client& operator=(Client&& other); + + template + typename RealmGateway::Client asGeneric() { + return castAs>(); + } + + CAPNP_AUTO_IF_MSVC(::capnp::Request::ImportParams, typename ::capnp::Persistent::SaveResults>) importRequest( + ::kj::Maybe< ::capnp::MessageSize> sizeHint = nullptr); + CAPNP_AUTO_IF_MSVC(::capnp::Request::ExportParams, typename ::capnp::Persistent::SaveResults>) exportRequest( + ::kj::Maybe< ::capnp::MessageSize> sizeHint = nullptr); + +protected: + Client() = default; +}; + +template +class RealmGateway::Server + : public virtual ::capnp::Capability::Server { +public: + typedef RealmGateway Serves; + + ::kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) + override; + +protected: + typedef typename ::capnp::RealmGateway::ImportParams ImportParams; + typedef ::capnp::CallContext::SaveResults> ImportContext; + virtual ::kj::Promise import(ImportContext context); + typedef typename ::capnp::RealmGateway::ExportParams ExportParams; + typedef ::capnp::CallContext::SaveResults> ExportContext; + virtual ::kj::Promise export_(ExportContext context); + + inline typename ::capnp::RealmGateway::Client thisCap() { + return ::capnp::Capability::Server::thisCap() + .template castAs< ::capnp::RealmGateway>(); + } + + ::kj::Promise dispatchCallInternal(uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context); +}; +#endif // !CAPNP_LITE + +template +class RealmGateway::ImportParams::Reader { +public: + typedef ImportParams Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ImportParams::Reader asRealmGatewayGeneric() { + return typename RealmGateway::ImportParams::Reader(_reader); + } + + inline bool hasCap() const; +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap() const; +#endif // !CAPNP_LITE + + inline bool hasParams() const; + inline typename ::capnp::Persistent::SaveParams::Reader getParams() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class RealmGateway::ImportParams::Builder { +public: + typedef ImportParams Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ImportParams::Builder asRealmGatewayGeneric() { + return typename RealmGateway::ImportParams::Builder(_builder); + } + + inline bool hasCap(); +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap(); + inline void setCap(typename ::capnp::Persistent::Client&& value); + inline void setCap(typename ::capnp::Persistent::Client& value); + inline void adoptCap(::capnp::Orphan< ::capnp::Persistent>&& value); + inline ::capnp::Orphan< ::capnp::Persistent> disownCap(); +#endif // !CAPNP_LITE + + inline bool hasParams(); + inline typename ::capnp::Persistent::SaveParams::Builder getParams(); + inline void setParams(typename ::capnp::Persistent::SaveParams::Reader value); + inline typename ::capnp::Persistent::SaveParams::Builder initParams(); + inline void adoptParams(::capnp::Orphan::SaveParams>&& value); + inline ::capnp::Orphan::SaveParams> disownParams(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class RealmGateway::ImportParams::Pipeline { +public: + typedef ImportParams Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline typename ::capnp::Persistent::Client getCap(); + inline typename ::capnp::Persistent::SaveParams::Pipeline getParams(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +template +class RealmGateway::ExportParams::Reader { +public: + typedef ExportParams Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ExportParams::Reader asRealmGatewayGeneric() { + return typename RealmGateway::ExportParams::Reader(_reader); + } + + inline bool hasCap() const; +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap() const; +#endif // !CAPNP_LITE + + inline bool hasParams() const; + inline typename ::capnp::Persistent::SaveParams::Reader getParams() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class RealmGateway::ExportParams::Builder { +public: + typedef ExportParams Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ExportParams::Builder asRealmGatewayGeneric() { + return typename RealmGateway::ExportParams::Builder(_builder); + } + + inline bool hasCap(); +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap(); + inline void setCap(typename ::capnp::Persistent::Client&& value); + inline void setCap(typename ::capnp::Persistent::Client& value); + inline void adoptCap(::capnp::Orphan< ::capnp::Persistent>&& value); + inline ::capnp::Orphan< ::capnp::Persistent> disownCap(); +#endif // !CAPNP_LITE + + inline bool hasParams(); + inline typename ::capnp::Persistent::SaveParams::Builder getParams(); + inline void setParams(typename ::capnp::Persistent::SaveParams::Reader value); + inline typename ::capnp::Persistent::SaveParams::Builder initParams(); + inline void adoptParams(::capnp::Orphan::SaveParams>&& value); + inline ::capnp::Orphan::SaveParams> disownParams(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class RealmGateway::ExportParams::Pipeline { +public: + typedef ExportParams Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline typename ::capnp::Persistent::Client getCap(); + inline typename ::capnp::Persistent::SaveParams::Pipeline getParams(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +#if !CAPNP_LITE +template +inline Persistent::Client::Client(decltype(nullptr)) + : ::capnp::Capability::Client(nullptr) {} +template +inline Persistent::Client::Client( + ::kj::Own< ::capnp::ClientHook>&& hook) + : ::capnp::Capability::Client(::kj::mv(hook)) {} +template +template +inline Persistent::Client::Client(::kj::Own<_t>&& server) + : ::capnp::Capability::Client(::kj::mv(server)) {} +template +template +inline Persistent::Client::Client(::kj::Promise<_t>&& promise) + : ::capnp::Capability::Client(::kj::mv(promise)) {} +template +inline Persistent::Client::Client(::kj::Exception&& exception) + : ::capnp::Capability::Client(::kj::mv(exception)) {} +template +inline typename ::capnp::Persistent::Client& Persistent::Client::operator=(Client& other) { + ::capnp::Capability::Client::operator=(other); + return *this; +} +template +inline typename ::capnp::Persistent::Client& Persistent::Client::operator=(Client&& other) { + ::capnp::Capability::Client::operator=(kj::mv(other)); + return *this; +} + +#endif // !CAPNP_LITE +template +inline bool Persistent::SaveParams::Reader::hasSealFor() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool Persistent::SaveParams::Builder::hasSealFor() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline ::capnp::ReaderFor Persistent::SaveParams::Reader::getSealFor() const { + return ::capnp::_::PointerHelpers::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveParams::Builder::getSealFor() { + return ::capnp::_::PointerHelpers::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline ::capnp::PipelineFor Persistent::SaveParams::Pipeline::getSealFor() { + return ::capnp::PipelineFor(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +template +inline void Persistent::SaveParams::Builder::setSealFor( ::capnp::ReaderFor value) { + ::capnp::_::PointerHelpers::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +template +inline ::capnp::BuilderFor Persistent::SaveParams::Builder::initSealFor() { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveParams::Builder::initSealFor(unsigned int size) { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +template +inline void Persistent::SaveParams::Builder::adoptSealFor( + ::capnp::Orphan&& value) { + ::capnp::_::PointerHelpers::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan Persistent::SaveParams::Builder::disownSealFor() { + return ::capnp::_::PointerHelpers::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +// Persistent::SaveParams +template +constexpr uint16_t Persistent::SaveParams::_capnpPrivate::dataWordSize; +template +constexpr uint16_t Persistent::SaveParams::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind Persistent::SaveParams::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* Persistent::SaveParams::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope Persistent::SaveParams::_capnpPrivate::brandScopes[] = { + { 0xc8cb212fcd9f5691, brandBindings + 0, 2, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding Persistent::SaveParams::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema Persistent::SaveParams::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_f76fba59183073a5, brandScopes, nullptr, + 1, 0, nullptr +}; +#endif // !CAPNP_LITE + +template +inline bool Persistent::SaveResults::Reader::hasSturdyRef() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool Persistent::SaveResults::Builder::hasSturdyRef() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline ::capnp::ReaderFor Persistent::SaveResults::Reader::getSturdyRef() const { + return ::capnp::_::PointerHelpers::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveResults::Builder::getSturdyRef() { + return ::capnp::_::PointerHelpers::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline ::capnp::PipelineFor Persistent::SaveResults::Pipeline::getSturdyRef() { + return ::capnp::PipelineFor(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +template +inline void Persistent::SaveResults::Builder::setSturdyRef( ::capnp::ReaderFor value) { + ::capnp::_::PointerHelpers::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +template +inline ::capnp::BuilderFor Persistent::SaveResults::Builder::initSturdyRef() { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveResults::Builder::initSturdyRef(unsigned int size) { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +template +inline void Persistent::SaveResults::Builder::adoptSturdyRef( + ::capnp::Orphan&& value) { + ::capnp::_::PointerHelpers::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan Persistent::SaveResults::Builder::disownSturdyRef() { + return ::capnp::_::PointerHelpers::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +// Persistent::SaveResults +template +constexpr uint16_t Persistent::SaveResults::_capnpPrivate::dataWordSize; +template +constexpr uint16_t Persistent::SaveResults::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind Persistent::SaveResults::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* Persistent::SaveResults::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope Persistent::SaveResults::_capnpPrivate::brandScopes[] = { + { 0xc8cb212fcd9f5691, brandBindings + 0, 2, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding Persistent::SaveResults::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema Persistent::SaveResults::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_b76848c18c40efbf, brandScopes, nullptr, + 1, 0, nullptr +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +CAPNP_AUTO_IF_MSVC(::capnp::Request::SaveParams, typename ::capnp::Persistent::SaveResults>) +Persistent::Client::saveRequest(::kj::Maybe< ::capnp::MessageSize> sizeHint) { + return newCall::SaveParams, typename ::capnp::Persistent::SaveResults>( + 0xc8cb212fcd9f5691ull, 0, sizeHint); +} +template +::kj::Promise Persistent::Server::save(SaveContext) { + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:Persistent", "save", + 0xc8cb212fcd9f5691ull, 0); +} +template +::kj::Promise Persistent::Server::dispatchCall( + uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (interfaceId) { + case 0xc8cb212fcd9f5691ull: + return dispatchCallInternal(methodId, context); + default: + return internalUnimplemented("capnp/persistent.capnp:Persistent", interfaceId); + } +} +template +::kj::Promise Persistent::Server::dispatchCallInternal( + uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (methodId) { + case 0: + return save(::capnp::Capability::Server::internalGetTypedContext< + typename ::capnp::Persistent::SaveParams, typename ::capnp::Persistent::SaveResults>(context)); + default: + (void)context; + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:Persistent", + 0xc8cb212fcd9f5691ull, methodId); + } +} +#endif // !CAPNP_LITE + +// Persistent +#if !CAPNP_LITE +template +constexpr ::capnp::Kind Persistent::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* Persistent::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope Persistent::_capnpPrivate::brandScopes[] = { + { 0xc8cb212fcd9f5691, brandBindings + 0, 2, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding Persistent::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency Persistent::_capnpPrivate::brandDependencies[] = { + { 33554432, ::capnp::Persistent::SaveParams::_capnpPrivate::brand() }, + { 50331648, ::capnp::Persistent::SaveResults::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema Persistent::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_c8cb212fcd9f5691, brandScopes, brandDependencies, + 1, 2, nullptr +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +inline RealmGateway::Client::Client(decltype(nullptr)) + : ::capnp::Capability::Client(nullptr) {} +template +inline RealmGateway::Client::Client( + ::kj::Own< ::capnp::ClientHook>&& hook) + : ::capnp::Capability::Client(::kj::mv(hook)) {} +template +template +inline RealmGateway::Client::Client(::kj::Own<_t>&& server) + : ::capnp::Capability::Client(::kj::mv(server)) {} +template +template +inline RealmGateway::Client::Client(::kj::Promise<_t>&& promise) + : ::capnp::Capability::Client(::kj::mv(promise)) {} +template +inline RealmGateway::Client::Client(::kj::Exception&& exception) + : ::capnp::Capability::Client(::kj::mv(exception)) {} +template +inline typename ::capnp::RealmGateway::Client& RealmGateway::Client::operator=(Client& other) { + ::capnp::Capability::Client::operator=(other); + return *this; +} +template +inline typename ::capnp::RealmGateway::Client& RealmGateway::Client::operator=(Client&& other) { + ::capnp::Capability::Client::operator=(kj::mv(other)); + return *this; +} + +#endif // !CAPNP_LITE +template +inline bool RealmGateway::ImportParams::Reader::hasCap() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ImportParams::Builder::hasCap() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::Client RealmGateway::ImportParams::Reader::getCap() const { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ImportParams::Builder::getCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ImportParams::Pipeline::getCap() { + return typename ::capnp::Persistent::Client(_typeless.getPointerField(0).asCap()); +} +template +inline void RealmGateway::ImportParams::Builder::setCap(typename ::capnp::Persistent::Client&& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(cap)); +} +template +inline void RealmGateway::ImportParams::Builder::setCap(typename ::capnp::Persistent::Client& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), cap); +} +template +inline void RealmGateway::ImportParams::Builder::adoptCap( + ::capnp::Orphan< ::capnp::Persistent>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan< ::capnp::Persistent> RealmGateway::ImportParams::Builder::disownCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#endif // !CAPNP_LITE + +template +inline bool RealmGateway::ImportParams::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ImportParams::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline typename ::capnp::Persistent::SaveParams::Reader RealmGateway::ImportParams::Reader::getParams() const { + return ::capnp::_::PointerHelpers::SaveParams>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ImportParams::Builder::getParams() { + return ::capnp::_::PointerHelpers::SaveParams>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::SaveParams::Pipeline RealmGateway::ImportParams::Pipeline::getParams() { + return typename ::capnp::Persistent::SaveParams::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +template +inline void RealmGateway::ImportParams::Builder::setParams(typename ::capnp::Persistent::SaveParams::Reader value) { + ::capnp::_::PointerHelpers::SaveParams>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ImportParams::Builder::initParams() { + return ::capnp::_::PointerHelpers::SaveParams>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline void RealmGateway::ImportParams::Builder::adoptParams( + ::capnp::Orphan::SaveParams>&& value) { + ::capnp::_::PointerHelpers::SaveParams>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan::SaveParams> RealmGateway::ImportParams::Builder::disownParams() { + return ::capnp::_::PointerHelpers::SaveParams>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +// RealmGateway::ImportParams +template +constexpr uint16_t RealmGateway::ImportParams::_capnpPrivate::dataWordSize; +template +constexpr uint16_t RealmGateway::ImportParams::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind RealmGateway::ImportParams::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* RealmGateway::ImportParams::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope RealmGateway::ImportParams::_capnpPrivate::brandScopes[] = { + { 0x84ff286cd00a3ed4, brandBindings + 0, 4, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding RealmGateway::ImportParams::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency RealmGateway::ImportParams::_capnpPrivate::brandDependencies[] = { + { 16777216, ::capnp::Persistent::_capnpPrivate::brand() }, + { 16777217, ::capnp::Persistent::SaveParams::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema RealmGateway::ImportParams::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_f0c2cc1d3909574d, brandScopes, brandDependencies, + 1, 2, nullptr +}; +#endif // !CAPNP_LITE + +template +inline bool RealmGateway::ExportParams::Reader::hasCap() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ExportParams::Builder::hasCap() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::Client RealmGateway::ExportParams::Reader::getCap() const { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ExportParams::Builder::getCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ExportParams::Pipeline::getCap() { + return typename ::capnp::Persistent::Client(_typeless.getPointerField(0).asCap()); +} +template +inline void RealmGateway::ExportParams::Builder::setCap(typename ::capnp::Persistent::Client&& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(cap)); +} +template +inline void RealmGateway::ExportParams::Builder::setCap(typename ::capnp::Persistent::Client& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), cap); +} +template +inline void RealmGateway::ExportParams::Builder::adoptCap( + ::capnp::Orphan< ::capnp::Persistent>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan< ::capnp::Persistent> RealmGateway::ExportParams::Builder::disownCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#endif // !CAPNP_LITE + +template +inline bool RealmGateway::ExportParams::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ExportParams::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline typename ::capnp::Persistent::SaveParams::Reader RealmGateway::ExportParams::Reader::getParams() const { + return ::capnp::_::PointerHelpers::SaveParams>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ExportParams::Builder::getParams() { + return ::capnp::_::PointerHelpers::SaveParams>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::SaveParams::Pipeline RealmGateway::ExportParams::Pipeline::getParams() { + return typename ::capnp::Persistent::SaveParams::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +template +inline void RealmGateway::ExportParams::Builder::setParams(typename ::capnp::Persistent::SaveParams::Reader value) { + ::capnp::_::PointerHelpers::SaveParams>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ExportParams::Builder::initParams() { + return ::capnp::_::PointerHelpers::SaveParams>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline void RealmGateway::ExportParams::Builder::adoptParams( + ::capnp::Orphan::SaveParams>&& value) { + ::capnp::_::PointerHelpers::SaveParams>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan::SaveParams> RealmGateway::ExportParams::Builder::disownParams() { + return ::capnp::_::PointerHelpers::SaveParams>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +// RealmGateway::ExportParams +template +constexpr uint16_t RealmGateway::ExportParams::_capnpPrivate::dataWordSize; +template +constexpr uint16_t RealmGateway::ExportParams::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind RealmGateway::ExportParams::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* RealmGateway::ExportParams::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope RealmGateway::ExportParams::_capnpPrivate::brandScopes[] = { + { 0x84ff286cd00a3ed4, brandBindings + 0, 4, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding RealmGateway::ExportParams::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency RealmGateway::ExportParams::_capnpPrivate::brandDependencies[] = { + { 16777216, ::capnp::Persistent::_capnpPrivate::brand() }, + { 16777217, ::capnp::Persistent::SaveParams::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema RealmGateway::ExportParams::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_ecafa18b482da3aa, brandScopes, brandDependencies, + 1, 2, nullptr +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +CAPNP_AUTO_IF_MSVC(::capnp::Request::ImportParams, typename ::capnp::Persistent::SaveResults>) +RealmGateway::Client::importRequest(::kj::Maybe< ::capnp::MessageSize> sizeHint) { + return newCall::ImportParams, typename ::capnp::Persistent::SaveResults>( + 0x84ff286cd00a3ed4ull, 0, sizeHint); +} +template +::kj::Promise RealmGateway::Server::import(ImportContext) { + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:RealmGateway", "import", + 0x84ff286cd00a3ed4ull, 0); +} +template +CAPNP_AUTO_IF_MSVC(::capnp::Request::ExportParams, typename ::capnp::Persistent::SaveResults>) +RealmGateway::Client::exportRequest(::kj::Maybe< ::capnp::MessageSize> sizeHint) { + return newCall::ExportParams, typename ::capnp::Persistent::SaveResults>( + 0x84ff286cd00a3ed4ull, 1, sizeHint); +} +template +::kj::Promise RealmGateway::Server::export_(ExportContext) { + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:RealmGateway", "export", + 0x84ff286cd00a3ed4ull, 1); +} +template +::kj::Promise RealmGateway::Server::dispatchCall( + uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (interfaceId) { + case 0x84ff286cd00a3ed4ull: + return dispatchCallInternal(methodId, context); + default: + return internalUnimplemented("capnp/persistent.capnp:RealmGateway", interfaceId); + } +} +template +::kj::Promise RealmGateway::Server::dispatchCallInternal( + uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (methodId) { + case 0: + return import(::capnp::Capability::Server::internalGetTypedContext< + typename ::capnp::RealmGateway::ImportParams, typename ::capnp::Persistent::SaveResults>(context)); + case 1: + return export_(::capnp::Capability::Server::internalGetTypedContext< + typename ::capnp::RealmGateway::ExportParams, typename ::capnp::Persistent::SaveResults>(context)); + default: + (void)context; + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:RealmGateway", + 0x84ff286cd00a3ed4ull, methodId); + } +} +#endif // !CAPNP_LITE + +// RealmGateway +#if !CAPNP_LITE +template +constexpr ::capnp::Kind RealmGateway::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* RealmGateway::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope RealmGateway::_capnpPrivate::brandScopes[] = { + { 0x84ff286cd00a3ed4, brandBindings + 0, 4, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding RealmGateway::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency RealmGateway::_capnpPrivate::brandDependencies[] = { + { 33554432, ::capnp::RealmGateway::ImportParams::_capnpPrivate::brand() }, + { 33554433, ::capnp::RealmGateway::ExportParams::_capnpPrivate::brand() }, + { 50331648, ::capnp::Persistent::SaveResults::_capnpPrivate::brand() }, + { 50331649, ::capnp::Persistent::SaveResults::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema RealmGateway::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_84ff286cd00a3ed4, brandScopes, brandDependencies, + 1, 4, nullptr +}; +#endif // !CAPNP_LITE + +} // namespace + +#endif // CAPNP_INCLUDED_b8630836983feed7_ diff --git a/phonelibs/capnp-cpp/include/capnp/pointer-helpers.h b/phonelibs/capnp-cpp/include/capnp/pointer-helpers.h new file mode 100644 index 00000000000000..fe70e5036ff221 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/pointer-helpers.h @@ -0,0 +1,160 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_POINTER_HELPERS_H_ +#define CAPNP_POINTER_HELPERS_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" +#include "list.h" + +namespace capnp { +namespace _ { // private + +// PointerHelpers is a template class that assists in wrapping/unwrapping the low-level types in +// layout.h with the high-level public API and generated types. This way, the code generator +// and other templates do not have to specialize on each kind of pointer. + +template +struct PointerHelpers { + static inline typename T::Reader get(PointerReader reader, const word* defaultValue = nullptr) { + return typename T::Reader(reader.getStruct(defaultValue)); + } + static inline typename T::Builder get(PointerBuilder builder, + const word* defaultValue = nullptr) { + return typename T::Builder(builder.getStruct(structSize(), defaultValue)); + } + static inline void set(PointerBuilder builder, typename T::Reader value) { + builder.setStruct(value._reader); + } + static inline void setCanonical(PointerBuilder builder, typename T::Reader value) { + builder.setStruct(value._reader, true); + } + static inline typename T::Builder init(PointerBuilder builder) { + return typename T::Builder(builder.initStruct(structSize())); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } + static inline _::StructReader getInternalReader(const typename T::Reader& reader) { + return reader._reader; + } + static inline _::StructBuilder getInternalBuilder(typename T::Builder&& builder) { + return builder._builder; + } +}; + +template +struct PointerHelpers, Kind::LIST> { + static inline typename List::Reader get(PointerReader reader, + const word* defaultValue = nullptr) { + return typename List::Reader(List::getFromPointer(reader, defaultValue)); + } + static inline typename List::Builder get(PointerBuilder builder, + const word* defaultValue = nullptr) { + return typename List::Builder(List::getFromPointer(builder, defaultValue)); + } + static inline void set(PointerBuilder builder, typename List::Reader value) { + builder.setList(value.reader); + } + static inline void setCanonical(PointerBuilder builder, typename List::Reader value) { + builder.setList(value.reader, true); + } + static void set(PointerBuilder builder, kj::ArrayPtr> value) { + auto l = init(builder, value.size()); + uint i = 0; + for (auto& element: value) { + l.set(i++, element); + } + } + static inline typename List::Builder init(PointerBuilder builder, uint size) { + return typename List::Builder(List::initPointer(builder, size)); + } + static inline void adopt(PointerBuilder builder, Orphan>&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan> disown(PointerBuilder builder) { + return Orphan>(builder.disown()); + } + static inline _::ListReader getInternalReader(const typename List::Reader& reader) { + return reader.reader; + } + static inline _::ListBuilder getInternalBuilder(typename List::Builder&& builder) { + return builder.builder; + } +}; + +template +struct PointerHelpers { + static inline typename T::Reader get(PointerReader reader, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return reader.getBlob(defaultValue, bounded(defaultBytes) * BYTES); + } + static inline typename T::Builder get(PointerBuilder builder, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return builder.getBlob(defaultValue, bounded(defaultBytes) * BYTES); + } + static inline void set(PointerBuilder builder, typename T::Reader value) { + builder.setBlob(value); + } + static inline void setCanonical(PointerBuilder builder, typename T::Reader value) { + builder.setBlob(value); + } + static inline typename T::Builder init(PointerBuilder builder, uint size) { + return builder.initBlob(bounded(size) * BYTES); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +struct UncheckedMessage { + typedef const word* Reader; +}; + +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; + +template <> +struct PointerHelpers { + // Reads an AnyPointer field as an unchecked message pointer. Requires that the containing + // message is itself unchecked. This hack is currently private. It is used to locate default + // values within encoded schemas. + + static inline const word* get(PointerReader reader) { + return reader.getUnchecked(); + } +}; + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_POINTER_HELPERS_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/pretty-print.h b/phonelibs/capnp-cpp/include/capnp/pretty-print.h new file mode 100644 index 00000000000000..e6458bca496b5e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/pretty-print.h @@ -0,0 +1,47 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_PRETTY_PRINT_H_ +#define CAPNP_PRETTY_PRINT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "dynamic.h" +#include + +namespace capnp { + +kj::StringTree prettyPrint(DynamicStruct::Reader value); +kj::StringTree prettyPrint(DynamicStruct::Builder value); +kj::StringTree prettyPrint(DynamicList::Reader value); +kj::StringTree prettyPrint(DynamicList::Builder value); +// Print the given Cap'n Proto struct or list with nice indentation. Note that you can pass any +// struct or list reader or builder type to this method, since they can be implicitly converted +// to one of the dynamic types. +// +// If you don't want indentation, just use the value's KJ stringifier (e.g. pass it to kj::str(), +// any of the KJ debug macros, etc.). + +} // namespace capnp + +#endif // PRETTY_PRINT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/raw-schema.h b/phonelibs/capnp-cpp/include/capnp/raw-schema.h new file mode 100644 index 00000000000000..ed9425a6241b19 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/raw-schema.h @@ -0,0 +1,242 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_RAW_SCHEMA_H_ +#define CAPNP_RAW_SCHEMA_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "common.h" // for uint and friends + +#if _MSC_VER +#include +#endif + +namespace capnp { +namespace _ { // private + +struct RawSchema; + +struct RawBrandedSchema { + // Represents a combination of a schema and bindings for its generic parameters. + // + // Note that while we generate one `RawSchema` per type, we generate a `RawBrandedSchema` for + // every _instance_ of a generic type -- or, at least, every instance that is actually used. For + // generated-code types, we use template magic to initialize these. + + const RawSchema* generic; + // Generic type which we're branding. + + struct Binding { + uint8_t which; // Numeric value of one of schema::Type::Which. + + bool isImplicitParameter; + // For AnyPointer, true if it's an implicit method parameter. + + uint16_t listDepth; // Number of times to wrap the base type in List(). + + uint16_t paramIndex; + // For AnyPointer. If it's a type parameter (scopeId is non-zero) or it's an implicit parameter + // (isImplicitParameter is true), then this is the parameter index. Otherwise this is a numeric + // value of one of schema::Type::AnyPointer::Unconstrained::Which. + + union { + const RawBrandedSchema* schema; // for struct, enum, interface + uint64_t scopeId; // for AnyPointer, if it's a type parameter + }; + + Binding() = default; + inline constexpr Binding(uint8_t which, uint16_t listDepth, const RawBrandedSchema* schema) + : which(which), isImplicitParameter(false), listDepth(listDepth), paramIndex(0), + schema(schema) {} + inline constexpr Binding(uint8_t which, uint16_t listDepth, + uint64_t scopeId, uint16_t paramIndex) + : which(which), isImplicitParameter(false), listDepth(listDepth), paramIndex(paramIndex), + scopeId(scopeId) {} + inline constexpr Binding(uint8_t which, uint16_t listDepth, uint16_t implicitParamIndex) + : which(which), isImplicitParameter(true), listDepth(listDepth), + paramIndex(implicitParamIndex), scopeId(0) {} + }; + + struct Scope { + uint64_t typeId; + // Type ID whose parameters are being bound. + + const Binding* bindings; + uint bindingCount; + // Bindings for those parameters. + + bool isUnbound; + // This scope is unbound, in the sense of SchemaLoader::getUnbound(). + }; + + const Scope* scopes; + // Array of enclosing scopes for which generic variables have been bound, sorted by type ID. + + struct Dependency { + uint location; + const RawBrandedSchema* schema; + }; + + const Dependency* dependencies; + // Map of branded schemas for dependencies of this type, given our brand. Only dependencies that + // are branded are included in this map; if a dependency is missing, use its `defaultBrand`. + + uint32_t scopeCount; + uint32_t dependencyCount; + + enum class DepKind { + // Component of a Dependency::location. Specifies what sort of dependency this is. + + INVALID, + // Mostly defined to ensure that zero is not a valid location. + + FIELD, + // Binding needed for a field's type. The index is the field index (NOT ordinal!). + + METHOD_PARAMS, + // Bindings needed for a method's params type. The index is the method number. + + METHOD_RESULTS, + // Bindings needed for a method's results type. The index is the method ordinal. + + SUPERCLASS, + // Bindings needed for a superclass type. The index is the superclass's index in the + // "extends" list. + + CONST_TYPE + // Bindings needed for the type of a constant. The index is zero. + }; + + static inline uint makeDepLocation(DepKind kind, uint index) { + // Make a number representing the location of a particular dependency within its parent + // schema. + + return (static_cast(kind) << 24) | index; + } + + class Initializer { + public: + virtual void init(const RawBrandedSchema* generic) const = 0; + }; + + const Initializer* lazyInitializer; + // Lazy initializer, invoked by ensureInitialized(). + + inline void ensureInitialized() const { + // Lazy initialization support. Invoke to ensure that initialization has taken place. This + // is required in particular when traversing the dependency list. RawSchemas for compiled-in + // types are always initialized; only dynamically-loaded schemas may be lazy. + +#if __GNUC__ + const Initializer* i = __atomic_load_n(&lazyInitializer, __ATOMIC_ACQUIRE); +#elif _MSC_VER + const Initializer* i = *static_cast(&lazyInitializer); + std::atomic_thread_fence(std::memory_order_acquire); +#else +#error "Platform not supported" +#endif + if (i != nullptr) i->init(this); + } + + inline bool isUnbound() const; + // Checks if this schema is the result of calling SchemaLoader::getUnbound(), in which case + // binding lookups need to be handled specially. +}; + +struct RawSchema { + // The generated code defines a constant RawSchema for every compiled declaration. + // + // This is an internal structure which could change in the future. + + uint64_t id; + + const word* encodedNode; + // Encoded SchemaNode, readable via readMessageUnchecked(encodedNode). + + uint32_t encodedSize; + // Size of encodedNode, in words. + + const RawSchema* const* dependencies; + // Pointers to other types on which this one depends, sorted by ID. The schemas in this table + // may be uninitialized -- you must call ensureInitialized() on the one you wish to use before + // using it. + // + // TODO(someday): Make this a hashtable. + + const uint16_t* membersByName; + // Indexes of members sorted by name. Used to implement name lookup. + // TODO(someday): Make this a hashtable. + + uint32_t dependencyCount; + uint32_t memberCount; + // Sizes of above tables. + + const uint16_t* membersByDiscriminant; + // List of all member indexes ordered by discriminant value. Those which don't have a + // discriminant value are listed at the end, in order by ordinal. + + const RawSchema* canCastTo; + // Points to the RawSchema of a compiled-in type to which it is safe to cast any DynamicValue + // with this schema. This is null for all compiled-in types; it is only set by SchemaLoader on + // dynamically-loaded types. + + class Initializer { + public: + virtual void init(const RawSchema* schema) const = 0; + }; + + const Initializer* lazyInitializer; + // Lazy initializer, invoked by ensureInitialized(). + + inline void ensureInitialized() const { + // Lazy initialization support. Invoke to ensure that initialization has taken place. This + // is required in particular when traversing the dependency list. RawSchemas for compiled-in + // types are always initialized; only dynamically-loaded schemas may be lazy. + +#if __GNUC__ + const Initializer* i = __atomic_load_n(&lazyInitializer, __ATOMIC_ACQUIRE); +#elif _MSC_VER + const Initializer* i = *static_cast(&lazyInitializer); + std::atomic_thread_fence(std::memory_order_acquire); +#else +#error "Platform not supported" +#endif + if (i != nullptr) i->init(this); + } + + RawBrandedSchema defaultBrand; + // Specifies the brand to use for this schema if no generic parameters have been bound to + // anything. Generally, in the default brand, all generic parameters are treated as if they were + // bound to `AnyPointer`. +}; + +inline bool RawBrandedSchema::isUnbound() const { + // The unbound schema is the only one that has no scopes but is not the default schema. + return scopeCount == 0 && this != &generic->defaultBrand; +} + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_RAW_SCHEMA_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-prelude.h b/phonelibs/capnp-cpp/include/capnp/rpc-prelude.h new file mode 100644 index 00000000000000..7d26e39de8a68e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-prelude.h @@ -0,0 +1,130 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains a bunch of internal declarations that must appear before rpc.h can start. +// We don't define these directly in rpc.h because it makes the file hard to read. + +#ifndef CAPNP_RPC_PRELUDE_H_ +#define CAPNP_RPC_PRELUDE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "capability.h" +#include "persistent.capnp.h" + +namespace capnp { + +class OutgoingRpcMessage; +class IncomingRpcMessage; + +template +class RpcSystem; + +namespace _ { // private + +class VatNetworkBase { + // Non-template version of VatNetwork. Ignore this class; see VatNetwork in rpc.h. + +public: + class Connection; + + struct ConnectionAndProvisionId { + kj::Own connection; + kj::Own firstMessage; + Orphan provisionId; + }; + + class Connection { + public: + virtual kj::Own newOutgoingMessage(uint firstSegmentWordSize) = 0; + virtual kj::Promise>> receiveIncomingMessage() = 0; + virtual kj::Promise shutdown() = 0; + virtual AnyStruct::Reader baseGetPeerVatId() = 0; + }; + virtual kj::Maybe> baseConnect(AnyStruct::Reader vatId) = 0; + virtual kj::Promise> baseAccept() = 0; +}; + +class SturdyRefRestorerBase { +public: + virtual Capability::Client baseRestore(AnyPointer::Reader ref) = 0; +}; + +class BootstrapFactoryBase { + // Non-template version of BootstrapFactory. Ignore this class; see BootstrapFactory in rpc.h. +public: + virtual Capability::Client baseCreateFor(AnyStruct::Reader clientId) = 0; +}; + +class RpcSystemBase { + // Non-template version of RpcSystem. Ignore this class; see RpcSystem in rpc.h. + +public: + RpcSystemBase(VatNetworkBase& network, kj::Maybe bootstrapInterface, + kj::Maybe::Client> gateway); + RpcSystemBase(VatNetworkBase& network, BootstrapFactoryBase& bootstrapFactory, + kj::Maybe::Client> gateway); + RpcSystemBase(VatNetworkBase& network, SturdyRefRestorerBase& restorer); + RpcSystemBase(RpcSystemBase&& other) noexcept; + ~RpcSystemBase() noexcept(false); + +private: + class Impl; + kj::Own impl; + + Capability::Client baseBootstrap(AnyStruct::Reader vatId); + Capability::Client baseRestore(AnyStruct::Reader vatId, AnyPointer::Reader objectId); + void baseSetFlowLimit(size_t words); + + template + friend class capnp::RpcSystem; +}; + +template struct InternalRefFromRealmGateway_; +template +struct InternalRefFromRealmGateway_> { + typedef InternalRef Type; +}; +template +using InternalRefFromRealmGateway = typename InternalRefFromRealmGateway_::Type; +template +using InternalRefFromRealmGatewayClient = InternalRefFromRealmGateway; + +template struct ExternalRefFromRealmGateway_; +template +struct ExternalRefFromRealmGateway_> { + typedef ExternalRef Type; +}; +template +using ExternalRefFromRealmGateway = typename ExternalRefFromRealmGateway_::Type; +template +using ExternalRefFromRealmGatewayClient = ExternalRefFromRealmGateway; + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_RPC_PRELUDE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp new file mode 100644 index 00000000000000..0b670e8ac3fc24 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp @@ -0,0 +1,169 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xa184c7885cdaf2a1; +# This file defines the "network-specific parameters" in rpc.capnp to support a network consisting +# of two vats. Each of these vats may in fact be in communication with other vats, but any +# capabilities they forward must be proxied. Thus, to each end of the connection, all capabilities +# received from the other end appear to live in a single vat. +# +# Two notable use cases for this model include: +# - Regular client-server communications, where a remote client machine (perhaps living on an end +# user's personal device) connects to a server. The server may be part of a cluster, and may +# call on other servers in the cluster to help service the user's request. It may even obtain +# capabilities from these other servers which it passes on to the user. To simplify network +# common traversal problems (e.g. if the user is behind a firewall), it is probably desirable to +# multiplex all communications between the server cluster and the client over the original +# connection rather than form new ones. This connection should use the two-party protocol, as +# the client has no interest in knowing about additional servers. +# - Applications running in a sandbox. A supervisor process may execute a confined application +# such that all of the confined app's communications with the outside world must pass through +# the supervisor. In this case, the connection between the confined app and the supervisor might +# as well use the two-party protocol, because the confined app is intentionally prevented from +# talking to any other vat anyway. Any external resources will be proxied through the supervisor, +# and so to the contained app will appear as if they were hosted by the supervisor itself. +# +# Since there are only two vats in this network, there is never a need for three-way introductions, +# so level 3 is free. Moreover, because it is never necessary to form new connections, the +# two-party protocol can be used easily anywhere where a two-way byte stream exists, without regard +# to where that byte stream goes or how it was initiated. This makes the two-party runtime library +# highly reusable. +# +# Joins (level 4) _could_ be needed in cases where one or both vats are participating in other +# networks that use joins. For instance, if Alice and Bob are speaking through the two-party +# protocol, and Bob is also participating on another network, Bob may send Alice two or more +# proxied capabilities which, unbeknownst to Bob at the time, are in fact pointing at the same +# remote object. Alice may then request to join these capabilities, at which point Bob will have +# to forward the join to the other network. Note, however, that if Alice is _not_ participating on +# any other network, then Alice will never need to _receive_ a Join, because Alice would always +# know when two locally-hosted capabilities are the same and would never export a redundant alias +# to Bob. So, Alice can respond to all incoming joins with an error, and only needs to implement +# outgoing joins if she herself desires to use this feature. Also, outgoing joins are relatively +# easy to implement in this scenario. +# +# What all this means is that a level 4 implementation of the confined network is barely more +# complicated than a level 2 implementation. However, such an implementation allows the "client" +# or "confined" app to access the server's/supervisor's network with equal functionality to any +# native participant. In other words, an application which implements only the two-party protocol +# can be paired with a proxy app in order to participate in any network. +# +# So, when implementing Cap'n Proto in a new language, it makes sense to implement only the +# two-party protocol initially, and then pair applications with an appropriate proxy written in +# C++, rather than implement other parameterizations of the RPC protocol directly. + +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("capnp::rpc::twoparty"); + +# Note: SturdyRef is not specified here. It is up to the application to define semantics of +# SturdyRefs if desired. + +enum Side { + server @0; + # The object lives on the "server" or "supervisor" end of the connection. Only the + # server/supervisor knows how to interpret the ref; to the client, it is opaque. + # + # Note that containers intending to implement strong confinement should rewrite SturdyRefs + # received from the external network before passing them on to the confined app. The confined + # app thus does not ever receive the raw bits of the SturdyRef (which it could perhaps + # maliciously leak), but instead receives only a thing that it can pass back to the container + # later to restore the ref. See: + # http://www.erights.org/elib/capability/dist-confine.html + + client @1; + # The object lives on the "client" or "confined app" end of the connection. Only the client + # knows how to interpret the ref; to the server/supervisor, it is opaque. Most clients do not + # actually know how to persist capabilities at all, so use of this is unusual. +} + +struct VatId { + side @0 :Side; +} + +struct ProvisionId { + # Only used for joins, since three-way introductions never happen on a two-party network. + + joinId @0 :UInt32; + # The ID from `JoinKeyPart`. +} + +struct RecipientId {} +# Never used, because there are only two parties. + +struct ThirdPartyCapId {} +# Never used, because there is no third party. + +struct JoinKeyPart { + # Joins in the two-party case are simplified by a few observations. + # + # First, on a two-party network, a Join only ever makes sense if the receiving end is also + # connected to other networks. A vat which is not connected to any other network can safely + # reject all joins. + # + # Second, since a two-party connection bisects the network -- there can be no other connections + # between the networks at either end of the connection -- if one part of a join crosses the + # connection, then _all_ parts must cross it. Therefore, a vat which is receiving a Join request + # off some other network which needs to be forwarded across the two-party connection can + # collect all the parts on its end and only forward them across the two-party connection when all + # have been received. + # + # For example, imagine that Alice and Bob are vats connected over a two-party connection, and + # each is also connected to other networks. At some point, Alice receives one part of a Join + # request off her network. The request is addressed to a capability that Alice received from + # Bob and is proxying to her other network. Alice goes ahead and responds to the Join part as + # if she hosted the capability locally (this is important so that if not all the Join parts end + # up at Alice, the original sender can detect the failed Join without hanging). As other parts + # trickle in, Alice verifies that each part is addressed to a capability from Bob and continues + # to respond to each one. Once the complete set of join parts is received, Alice checks if they + # were all for the exact same capability. If so, she doesn't need to send anything to Bob at + # all. Otherwise, she collects the set of capabilities (from Bob) to which the join parts were + # addressed and essentially initiates a _new_ Join request on those capabilities to Bob. Alice + # does not forward the Join parts she received herself, but essentially forwards the Join as a + # whole. + # + # On Bob's end, since he knows that Alice will always send all parts of a Join together, he + # simply waits until he's received them all, then performs a join on the respective capabilities + # as if it had been requested locally. + + joinId @0 :UInt32; + # A number identifying this join, chosen by the sender. May be reused once `Finish` messages are + # sent corresponding to all of the `Join` messages. + + partCount @1 :UInt16; + # The number of capabilities to be joined. + + partNum @2 :UInt16; + # Which part this request targets -- a number in the range [0, partCount). +} + +struct JoinResult { + joinId @0 :UInt32; + # Matches `JoinKeyPart`. + + succeeded @1 :Bool; + # All JoinResults in the set will have the same value for `succeeded`. The receiver actually + # implements the join by waiting for all the `JoinKeyParts` and then performing its own join on + # them, then going back and answering all the join requests afterwards. + + cap @2 :AnyPointer; + # One of the JoinResults will have a non-null `cap` which is the joined capability. + # + # TODO(cleanup): Change `AnyPointer` to `Capability` when that is supported. +} diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp.h b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp.h new file mode 100644 index 00000000000000..9d7820646a75ec --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp.h @@ -0,0 +1,726 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: rpc-twoparty.capnp + +#ifndef CAPNP_INCLUDED_a184c7885cdaf2a1_ +#define CAPNP_INCLUDED_a184c7885cdaf2a1_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(9fd69ebc87b9719c); +enum class Side_9fd69ebc87b9719c: uint16_t { + SERVER, + CLIENT, +}; +CAPNP_DECLARE_ENUM(Side, 9fd69ebc87b9719c); +CAPNP_DECLARE_SCHEMA(d20b909fee733a8e); +CAPNP_DECLARE_SCHEMA(b88d09a9c5f39817); +CAPNP_DECLARE_SCHEMA(89f389b6fd4082c1); +CAPNP_DECLARE_SCHEMA(b47f4979672cb59d); +CAPNP_DECLARE_SCHEMA(95b29059097fca83); +CAPNP_DECLARE_SCHEMA(9d263a3630b7ebee); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace rpc { +namespace twoparty { + +typedef ::capnp::schemas::Side_9fd69ebc87b9719c Side; + +struct VatId { + VatId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d20b909fee733a8e, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ProvisionId { + ProvisionId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b88d09a9c5f39817, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct RecipientId { + RecipientId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(89f389b6fd4082c1, 0, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ThirdPartyCapId { + ThirdPartyCapId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b47f4979672cb59d, 0, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JoinKeyPart { + JoinKeyPart() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(95b29059097fca83, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JoinResult { + JoinResult() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9d263a3630b7ebee, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class VatId::Reader { +public: + typedef VatId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::capnp::rpc::twoparty::Side getSide() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class VatId::Builder { +public: + typedef VatId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::capnp::rpc::twoparty::Side getSide(); + inline void setSide( ::capnp::rpc::twoparty::Side value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class VatId::Pipeline { +public: + typedef VatId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ProvisionId::Reader { +public: + typedef ProvisionId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ProvisionId::Builder { +public: + typedef ProvisionId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId(); + inline void setJoinId( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ProvisionId::Pipeline { +public: + typedef ProvisionId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class RecipientId::Reader { +public: + typedef RecipientId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class RecipientId::Builder { +public: + typedef RecipientId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class RecipientId::Pipeline { +public: + typedef RecipientId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ThirdPartyCapId::Reader { +public: + typedef ThirdPartyCapId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ThirdPartyCapId::Builder { +public: + typedef ThirdPartyCapId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ThirdPartyCapId::Pipeline { +public: + typedef ThirdPartyCapId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JoinKeyPart::Reader { +public: + typedef JoinKeyPart Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId() const; + + inline ::uint16_t getPartCount() const; + + inline ::uint16_t getPartNum() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JoinKeyPart::Builder { +public: + typedef JoinKeyPart Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId(); + inline void setJoinId( ::uint32_t value); + + inline ::uint16_t getPartCount(); + inline void setPartCount( ::uint16_t value); + + inline ::uint16_t getPartNum(); + inline void setPartNum( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JoinKeyPart::Pipeline { +public: + typedef JoinKeyPart Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JoinResult::Reader { +public: + typedef JoinResult Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId() const; + + inline bool getSucceeded() const; + + inline bool hasCap() const; + inline ::capnp::AnyPointer::Reader getCap() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JoinResult::Builder { +public: + typedef JoinResult Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId(); + inline void setJoinId( ::uint32_t value); + + inline bool getSucceeded(); + inline void setSucceeded(bool value); + + inline bool hasCap(); + inline ::capnp::AnyPointer::Builder getCap(); + inline ::capnp::AnyPointer::Builder initCap(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JoinResult::Pipeline { +public: + typedef JoinResult Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::rpc::twoparty::Side VatId::Reader::getSide() const { + return _reader.getDataField< ::capnp::rpc::twoparty::Side>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::rpc::twoparty::Side VatId::Builder::getSide() { + return _builder.getDataField< ::capnp::rpc::twoparty::Side>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void VatId::Builder::setSide( ::capnp::rpc::twoparty::Side value) { + _builder.setDataField< ::capnp::rpc::twoparty::Side>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t ProvisionId::Reader::getJoinId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t ProvisionId::Builder::getJoinId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void ProvisionId::Builder::setJoinId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t JoinKeyPart::Reader::getJoinId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t JoinKeyPart::Builder::getJoinId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void JoinKeyPart::Builder::setJoinId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t JoinKeyPart::Reader::getPartCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t JoinKeyPart::Builder::getPartCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void JoinKeyPart::Builder::setPartCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t JoinKeyPart::Reader::getPartNum() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t JoinKeyPart::Builder::getPartNum() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void JoinKeyPart::Builder::setPartNum( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t JoinResult::Reader::getJoinId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t JoinResult::Builder::getJoinId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void JoinResult::Builder::setJoinId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool JoinResult::Reader::getSucceeded() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} + +inline bool JoinResult::Builder::getSucceeded() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} +inline void JoinResult::Builder::setSucceeded(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value); +} + +inline bool JoinResult::Reader::hasCap() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JoinResult::Builder::hasCap() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader JoinResult::Reader::getCap() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder JoinResult::Builder::getCap() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder JoinResult::Builder::initCap() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +} // namespace +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_a184c7885cdaf2a1_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.h b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.h new file mode 100644 index 00000000000000..093c1fecdf9f35 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.h @@ -0,0 +1,160 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_RPC_TWOPARTY_H_ +#define CAPNP_RPC_TWOPARTY_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "rpc.h" +#include "message.h" +#include +#include + +namespace capnp { + +namespace rpc { + namespace twoparty { + typedef VatId SturdyRefHostId; // For backwards-compatibility with version 0.4. + } +} + +typedef VatNetwork + TwoPartyVatNetworkBase; + +class TwoPartyVatNetwork: public TwoPartyVatNetworkBase, + private TwoPartyVatNetworkBase::Connection { + // A `VatNetwork` that consists of exactly two parties communicating over an arbitrary byte + // stream. This is used to implement the common case of a client/server network. + // + // See `ez-rpc.h` for a simple interface for setting up two-party clients and servers. + // Use `TwoPartyVatNetwork` only if you need the advanced features. + +public: + TwoPartyVatNetwork(kj::AsyncIoStream& stream, rpc::twoparty::Side side, + ReaderOptions receiveOptions = ReaderOptions()); + KJ_DISALLOW_COPY(TwoPartyVatNetwork); + + kj::Promise onDisconnect() { return disconnectPromise.addBranch(); } + // Returns a promise that resolves when the peer disconnects. + + rpc::twoparty::Side getSide() { return side; } + + // implements VatNetwork ----------------------------------------------------- + + kj::Maybe> connect( + rpc::twoparty::VatId::Reader ref) override; + kj::Promise> accept() override; + +private: + class OutgoingMessageImpl; + class IncomingMessageImpl; + + kj::AsyncIoStream& stream; + rpc::twoparty::Side side; + MallocMessageBuilder peerVatId; + ReaderOptions receiveOptions; + bool accepted = false; + + kj::Maybe> previousWrite; + // Resolves when the previous write completes. This effectively serves as the write queue. + // Becomes null when shutdown() is called. + + kj::Own>> acceptFulfiller; + // Fulfiller for the promise returned by acceptConnectionAsRefHost() on the client side, or the + // second call on the server side. Never fulfilled, because there is only one connection. + + kj::ForkedPromise disconnectPromise = nullptr; + + class FulfillerDisposer: public kj::Disposer { + // Hack: TwoPartyVatNetwork is both a VatNetwork and a VatNetwork::Connection. When the RPC + // system detects (or initiates) a disconnection, it drops its reference to the Connection. + // When all references have been dropped, then we want disconnectPromise to be fulfilled. + // So we hand out Owns with this disposer attached, so that we can detect when + // they are dropped. + + public: + mutable kj::Own> fulfiller; + mutable uint refcount = 0; + + void disposeImpl(void* pointer) const override; + }; + FulfillerDisposer disconnectFulfiller; + + kj::Own asConnection(); + // Returns a pointer to this with the disposer set to disconnectFulfiller. + + // implements Connection ----------------------------------------------------- + + rpc::twoparty::VatId::Reader getPeerVatId() override; + kj::Own newOutgoingMessage(uint firstSegmentWordSize) override; + kj::Promise>> receiveIncomingMessage() override; + kj::Promise shutdown() override; +}; + +class TwoPartyServer: private kj::TaskSet::ErrorHandler { + // Convenience class which implements a simple server which accepts connections on a listener + // socket and serices them as two-party connections. + +public: + explicit TwoPartyServer(Capability::Client bootstrapInterface); + + void accept(kj::Own&& connection); + // Accepts the connection for servicing. + + kj::Promise listen(kj::ConnectionReceiver& listener); + // Listens for connections on the given listener. The returned promise never resolves unless an + // exception is thrown while trying to accept. You may discard the returned promise to cancel + // listening. + +private: + Capability::Client bootstrapInterface; + kj::TaskSet tasks; + + struct AcceptedConnection; + + void taskFailed(kj::Exception&& exception) override; +}; + +class TwoPartyClient { + // Convenience class which implements a simple client. + +public: + explicit TwoPartyClient(kj::AsyncIoStream& connection); + TwoPartyClient(kj::AsyncIoStream& connection, Capability::Client bootstrapInterface, + rpc::twoparty::Side side = rpc::twoparty::Side::CLIENT); + + Capability::Client bootstrap(); + // Get the server's bootstrap interface. + + inline kj::Promise onDisconnect() { return network.onDisconnect(); } + +private: + TwoPartyVatNetwork network; + RpcSystem rpcSystem; +}; + +} // namespace capnp + +#endif // CAPNP_RPC_TWOPARTY_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc.capnp b/phonelibs/capnp-cpp/include/capnp/rpc.capnp new file mode 100644 index 00000000000000..cd808b39f70466 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc.capnp @@ -0,0 +1,1399 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xb312981b2552a250; +# Recall that Cap'n Proto RPC allows messages to contain references to remote objects that +# implement interfaces. These references are called "capabilities", because they both designate +# the remote object to use and confer permission to use it. +# +# Recall also that Cap'n Proto RPC has the feature that when a method call itself returns a +# capability, the caller can begin calling methods on that capability _before the first call has +# returned_. The caller essentially sends a message saying "Hey server, as soon as you finish +# that previous call, do this with the result!". Cap'n Proto's RPC protocol makes this possible. +# +# The protocol is significantly more complicated than most RPC protocols. However, this is +# implementation complexity that underlies an easy-to-grasp higher-level model of object oriented +# programming. That is, just like TCP is a surprisingly complicated protocol that implements a +# conceptually-simple byte stream abstraction, Cap'n Proto is a surprisingly complicated protocol +# that implements a conceptually-simple object abstraction. +# +# Cap'n Proto RPC is based heavily on CapTP, the object-capability protocol used by the E +# programming language: +# http://www.erights.org/elib/distrib/captp/index.html +# +# Cap'n Proto RPC takes place between "vats". A vat hosts some set of objects and talks to other +# vats through direct bilateral connections. Typically, there is a 1:1 correspondence between vats +# and processes (in the unix sense of the word), although this is not strictly always true (one +# process could run multiple vats, or a distributed virtual vat might live across many processes). +# +# Cap'n Proto does not distinguish between "clients" and "servers" -- this is up to the application. +# Either end of any connection can potentially hold capabilities pointing to the other end, and +# can call methods on those capabilities. In the doc comments below, we use the words "sender" +# and "receiver". These refer to the sender and receiver of an instance of the struct or field +# being documented. Sometimes we refer to a "third-party" that is neither the sender nor the +# receiver. Documentation is generally written from the point of view of the sender. +# +# It is generally up to the vat network implementation to securely verify that connections are made +# to the intended vat as well as to encrypt transmitted data for privacy and integrity. See the +# `VatNetwork` example interface near the end of this file. +# +# When a new connection is formed, the only interesting things that can be done are to send a +# `Bootstrap` (level 0) or `Accept` (level 3) message. +# +# Unless otherwise specified, messages must be delivered to the receiving application in the same +# order in which they were initiated by the sending application. The goal is to support "E-Order", +# which states that two calls made on the same reference must be delivered in the order which they +# were made: +# http://erights.org/elib/concurrency/partial-order.html +# +# Since the full protocol is complicated, we define multiple levels of support that an +# implementation may target. For many applications, level 1 support will be sufficient. +# Comments in this file indicate which level requires the corresponding feature to be +# implemented. +# +# * **Level 0:** The implementation does not support object references. Only the bootstrap interface +# can be called. At this level, the implementation does not support object-oriented protocols and +# is similar in complexity to JSON-RPC or Protobuf services. This level should be considered only +# a temporary stepping-stone toward level 1 as the lack of object references drastically changes +# how protocols are designed. Applications _should not_ attempt to design their protocols around +# the limitations of level 0 implementations. +# +# * **Level 1:** The implementation supports simple bilateral interaction with object references +# and promise pipelining, but interactions between three or more parties are supported only via +# proxying of objects. E.g. if Alice (in Vat A) wants to send Bob (in Vat B) a capability +# pointing to Carol (in Vat C), Alice must create a proxy of Carol within Vat A and send Bob a +# reference to that; Bob cannot form a direct connection to Carol. Level 1 implementations do +# not support checking if two capabilities received from different vats actually point to the +# same object ("join"), although they should be able to do this check on capabilities received +# from the same vat. +# +# * **Level 2:** The implementation supports saving persistent capabilities -- i.e. capabilities +# that remain valid even after disconnect, and can be restored on a future connection. When a +# capability is saved, the requester receives a `SturdyRef`, which is a token that can be used +# to restore the capability later. +# +# * **Level 3:** The implementation supports three-way interactions. That is, if Alice (in Vat A) +# sends Bob (in Vat B) a capability pointing to Carol (in Vat C), then Vat B will automatically +# form a direct connection to Vat C rather than have requests be proxied through Vat A. +# +# * **Level 4:** The entire protocol is implemented, including joins (checking if two capabilities +# are equivalent). +# +# Note that an implementation must also support specific networks (transports), as described in +# the "Network-specific Parameters" section below. An implementation might have different levels +# depending on the network used. +# +# New implementations of Cap'n Proto should start out targeting the simplistic two-party network +# type as defined in `rpc-twoparty.capnp`. With this network type, level 3 is irrelevant and +# levels 2 and 4 are much easier than usual to implement. When such an implementation is paired +# with a container proxy, the contained app effectively gets to make full use of the proxy's +# network at level 4. And since Cap'n Proto IPC is extremely fast, it may never make sense to +# bother implementing any other vat network protocol -- just use the correct container type and get +# it for free. + +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("capnp::rpc"); + +# ======================================================================================== +# The Four Tables +# +# Cap'n Proto RPC connections are stateful (although an application built on Cap'n Proto could +# export a stateless interface). As in CapTP, for each open connection, a vat maintains four state +# tables: questions, answers, imports, and exports. See the diagram at: +# http://www.erights.org/elib/distrib/captp/4tables.html +# +# The question table corresponds to the other end's answer table, and the imports table corresponds +# to the other end's exports table. +# +# The entries in each table are identified by ID numbers (defined below as 32-bit integers). These +# numbers are always specific to the connection; a newly-established connection starts with no +# valid IDs. Since low-numbered IDs will pack better, it is suggested that IDs be assigned like +# Unix file descriptors -- prefer the lowest-number ID that is currently available. +# +# IDs in the questions/answers tables are chosen by the questioner and generally represent method +# calls that are in progress. +# +# IDs in the imports/exports tables are chosen by the exporter and generally represent objects on +# which methods may be called. Exports may be "settled", meaning the exported object is an actual +# object living in the exporter's vat, or they may be "promises", meaning the exported object is +# the as-yet-unknown result of an ongoing operation and will eventually be resolved to some other +# object once that operation completes. Calls made to a promise will be forwarded to the eventual +# target once it is known. The eventual replacement object does *not* get the same ID as the +# promise, as it may turn out to be an object that is already exported (so already has an ID) or +# may even live in a completely different vat (and so won't get an ID on the same export table +# at all). +# +# IDs can be reused over time. To make this safe, we carefully define the lifetime of IDs. Since +# messages using the ID could be traveling in both directions simultaneously, we must define the +# end of life of each ID _in each direction_. The ID is only safe to reuse once it has been +# released by both sides. +# +# When a Cap'n Proto connection is lost, everything on the four tables is lost. All questions are +# canceled and throw exceptions. All imports become broken (all future calls to them throw +# exceptions). All exports and answers are implicitly released. The only things not lost are +# persistent capabilities (`SturdyRef`s). The application must plan for this and should respond by +# establishing a new connection and restoring from these persistent capabilities. + +using QuestionId = UInt32; +# **(level 0)** +# +# Identifies a question in the sender's question table (which corresponds to the receiver's answer +# table). The questioner (caller) chooses an ID when making a call. The ID remains valid in +# caller -> callee messages until a Finish message is sent, and remains valid in callee -> caller +# messages until a Return message is sent. + +using AnswerId = QuestionId; +# **(level 0)** +# +# Identifies an answer in the sender's answer table (which corresponds to the receiver's question +# table). +# +# AnswerId is physically equivalent to QuestionId, since the question and answer tables correspond, +# but we define a separate type for documentation purposes: we always use the type representing +# the sender's point of view. + +using ExportId = UInt32; +# **(level 1)** +# +# Identifies an exported capability or promise in the sender's export table (which corresponds +# to the receiver's import table). The exporter chooses an ID before sending a capability over the +# wire. If the capability is already in the table, the exporter should reuse the same ID. If the +# ID is a promise (as opposed to a settled capability), this must be indicated at the time the ID +# is introduced (e.g. by using `senderPromise` instead of `senderHosted` in `CapDescriptor`); in +# this case, the importer shall expect a later `Resolve` message that replaces the promise. +# +# ExportId/ImportIds are subject to reference counting. Whenever an `ExportId` is sent over the +# wire (from the exporter to the importer), the export's reference count is incremented (unless +# otherwise specified). The reference count is later decremented by a `Release` message. Since +# the `Release` message can specify an arbitrary number by which to reduce the reference count, the +# importer should usually batch reference decrements and only send a `Release` when it believes the +# reference count has hit zero. Of course, it is possible that a new reference to the export is +# in-flight at the time that the `Release` message is sent, so it is necessary for the exporter to +# keep track of the reference count on its end as well to avoid race conditions. +# +# When a connection is lost, all exports are implicitly released. It is not possible to restore +# a connection state after disconnect (although a transport layer could implement a concept of +# persistent connections if it is transparent to the RPC layer). + +using ImportId = ExportId; +# **(level 1)** +# +# Identifies an imported capability or promise in the sender's import table (which corresponds to +# the receiver's export table). +# +# ImportId is physically equivalent to ExportId, since the export and import tables correspond, +# but we define a separate type for documentation purposes: we always use the type representing +# the sender's point of view. +# +# An `ImportId` remains valid in importer -> exporter messages until the importer has sent +# `Release` messages that (it believes) have reduced the reference count to zero. + +# ======================================================================================== +# Messages + +struct Message { + # An RPC connection is a bi-directional stream of Messages. + + union { + unimplemented @0 :Message; + # The sender previously received this message from the peer but didn't understand it or doesn't + # yet implement the functionality that was requested. So, the sender is echoing the message + # back. In some cases, the receiver may be able to recover from this by pretending the sender + # had taken some appropriate "null" action. + # + # For example, say `resolve` is received by a level 0 implementation (because a previous call + # or return happened to contain a promise). The level 0 implementation will echo it back as + # `unimplemented`. The original sender can then simply release the cap to which the promise + # had resolved, thus avoiding a leak. + # + # For any message type that introduces a question, if the message comes back unimplemented, + # the original sender may simply treat it as if the question failed with an exception. + # + # In cases where there is no sensible way to react to an `unimplemented` message (without + # resource leaks or other serious problems), the connection may need to be aborted. This is + # a gray area; different implementations may take different approaches. + + abort @1 :Exception; + # Sent when a connection is being aborted due to an unrecoverable error. This could be e.g. + # because the sender received an invalid or nonsensical message (`isCallersFault` is true) or + # because the sender had an internal error (`isCallersFault` is false). The sender will shut + # down the outgoing half of the connection after `abort` and will completely close the + # connection shortly thereafter (it's up to the sender how much of a time buffer they want to + # offer for the client to receive the `abort` before the connection is reset). + + # Level 0 features ----------------------------------------------- + + bootstrap @8 :Bootstrap; # Request the peer's bootstrap interface. + call @2 :Call; # Begin a method call. + return @3 :Return; # Complete a method call. + finish @4 :Finish; # Release a returned answer / cancel a call. + + # Level 1 features ----------------------------------------------- + + resolve @5 :Resolve; # Resolve a previously-sent promise. + release @6 :Release; # Release a capability so that the remote object can be deallocated. + disembargo @13 :Disembargo; # Lift an embargo used to enforce E-order over promise resolution. + + # Level 2 features ----------------------------------------------- + + obsoleteSave @7 :AnyPointer; + # Obsolete request to save a capability, resulting in a SturdyRef. This has been replaced + # by the `Persistent` interface defined in `persistent.capnp`. This operation was never + # implemented. + + obsoleteDelete @9 :AnyPointer; + # Obsolete way to delete a SturdyRef. This operation was never implemented. + + # Level 3 features ----------------------------------------------- + + provide @10 :Provide; # Provide a capability to a third party. + accept @11 :Accept; # Accept a capability provided by a third party. + + # Level 4 features ----------------------------------------------- + + join @12 :Join; # Directly connect to the common root of two or more proxied caps. + } +} + +# Level 0 message types ---------------------------------------------- + +struct Bootstrap { + # **(level 0)** + # + # Get the "bootstrap" interface exported by the remote vat. + # + # For level 0, 1, and 2 implementations, the "bootstrap" interface is simply the main interface + # exported by a vat. If the vat acts as a server fielding connections from clients, then the + # bootstrap interface defines the basic functionality available to a client when it connects. + # The exact interface definition obviously depends on the application. + # + # We call this a "bootstrap" because in an ideal Cap'n Proto world, bootstrap interfaces would + # never be used. In such a world, any time you connect to a new vat, you do so because you + # received an introduction from some other vat (see `ThirdPartyCapId`). Thus, the first message + # you send is `Accept`, and further communications derive from there. `Bootstrap` is not used. + # + # In such an ideal world, DNS itself would support Cap'n Proto -- performing a DNS lookup would + # actually return a new Cap'n Proto capability, thus introducing you to the target system via + # level 3 RPC. Applications would receive the capability to talk to DNS in the first place as + # an initial endowment or part of a Powerbox interaction. Therefore, an app can form arbitrary + # connections without ever using `Bootstrap`. + # + # Of course, in the real world, DNS is not Cap'n-Proto-based, and we don't want Cap'n Proto to + # require a whole new internet infrastructure to be useful. Therefore, we offer bootstrap + # interfaces as a way to get up and running without a level 3 introduction. Thus, bootstrap + # interfaces are used to "bootstrap" from other, non-Cap'n-Proto-based means of service discovery, + # such as legacy DNS. + # + # Note that a vat need not provide a bootstrap interface, and in fact many vats (especially those + # acting as clients) do not. In this case, the vat should either reply to `Bootstrap` with a + # `Return` indicating an exception, or should return a dummy capability with no methods. + + questionId @0 :QuestionId; + # A new question ID identifying this request, which will eventually receive a Return message + # containing the restored capability. + + deprecatedObjectId @1 :AnyPointer; + # ** DEPRECATED ** + # + # A Vat may export multiple bootstrap interfaces. In this case, `deprecatedObjectId` specifies + # which one to return. If this pointer is null, then the default bootstrap interface is returned. + # + # As of verison 0.5, use of this field is deprecated. If a service wants to export multiple + # bootstrap interfaces, it should instead define a single bootstarp interface that has methods + # that return each of the other interfaces. + # + # **History** + # + # In the first version of Cap'n Proto RPC (0.4.x) the `Bootstrap` message was called `Restore`. + # At the time, it was thought that this would eventually serve as the way to restore SturdyRefs + # (level 2). Meanwhile, an application could offer its "main" interface on a well-known + # (non-secret) SturdyRef. + # + # Since level 2 RPC was not implemented at the time, the `Restore` message was in practice only + # used to obtain the main interface. Since most applications had only one main interface that + # they wanted to restore, they tended to designate this with a null `objectId`. + # + # Unfortunately, the earliest version of the EZ RPC interfaces set a precedent of exporting + # multiple main interfaces by allowing them to be exported under string names. In this case, + # `objectId` was a Text value specifying the name. + # + # All of this proved problematic for several reasons: + # + # - The arrangement assumed that a client wishing to restore a SturdyRef would know exactly what + # machine to connect to and would be able to immediately restore a SturdyRef on connection. + # However, in practice, the ability to restore SturdyRefs is itself a capability that may + # require going through an authentication process to obtain. Thus, it makes more sense to + # define a "restorer service" as a full Cap'n Proto interface. If this restorer interface is + # offered as the vat's bootstrap interface, then this is equivalent to the old arrangement. + # + # - Overloading "Restore" for the purpose of obtaining well-known capabilities encouraged the + # practice of exporting singleton services with string names. If singleton services are desired, + # it is better to have one main interface that has methods that can be used to obtain each + # service, in order to get all the usual benefits of schemas and type checking. + # + # - Overloading "Restore" also had a security problem: Often, "main" or "well-known" + # capabilities exported by a vat are in fact not public: they are intended to be accessed only + # by clients who are capable of forming a connection to the vat. This can lead to trouble if + # the client itself has other clients and wishes to foward some `Restore` requests from those + # external clients -- it has to be very careful not to allow through `Restore` requests + # addressing the default capability. + # + # For example, consider the case of a sandboxed Sandstorm application and its supervisor. The + # application exports a default capability to its supervisor that provides access to + # functionality that only the supervisor is supposed to access. Meanwhile, though, applications + # may publish other capabilities that may be persistent, in which case the application needs + # to field `Restore` requests that could come from anywhere. These requests of course have to + # pass through the supervisor, as all communications with the outside world must. But, the + # supervisor has to be careful not to honor an external request addressing the application's + # default capability, since this capability is privileged. Unfortunately, the default + # capability cannot be given an unguessable name, because then the supervisor itself would not + # be able to address it! + # + # As of Cap'n Proto 0.5, `Restore` has been renamed to `Bootstrap` and is no longer planned for + # use in restoring SturdyRefs. + # + # Note that 0.4 also defined a message type called `Delete` that, like `Restore`, addressed a + # SturdyRef, but indicated that the client would not restore the ref again in the future. This + # operation was never implemented, so it was removed entirely. If a "delete" operation is desired, + # it should exist as a method on the same interface that handles restoring SturdyRefs. However, + # the utility of such an operation is questionable. You wouldn't be able to rely on it for + # garbage collection since a client could always disappear permanently without remembering to + # delete all its SturdyRefs, thus leaving them dangling forever. Therefore, it is advisable to + # design systems such that SturdyRefs never represent "owned" pointers. + # + # For example, say a SturdyRef points to an image file hosted on some server. That image file + # should also live inside a collection (a gallery, perhaps) hosted on the same server, owned by + # a user who can delete the image at any time. If the user deletes the image, the SturdyRef + # stops working. On the other hand, if the SturdyRef is discarded, this has no effect on the + # existence of the image in its collection. +} + +struct Call { + # **(level 0)** + # + # Message type initiating a method call on a capability. + + questionId @0 :QuestionId; + # A number, chosen by the caller, that identifies this call in future messages. This number + # must be different from all other calls originating from the same end of the connection (but + # may overlap with question IDs originating from the opposite end). A fine strategy is to use + # sequential question IDs, but the recipient should not assume this. + # + # A question ID can be reused once both: + # - A matching Return has been received from the callee. + # - A matching Finish has been sent from the caller. + + target @1 :MessageTarget; + # The object that should receive this call. + + interfaceId @2 :UInt64; + # The type ID of the interface being called. Each capability may implement multiple interfaces. + + methodId @3 :UInt16; + # The ordinal number of the method to call within the requested interface. + + allowThirdPartyTailCall @8 :Bool = false; + # Indicates whether or not the receiver is allowed to send a `Return` containing + # `acceptFromThirdParty`. Level 3 implementations should set this true. Otherwise, the callee + # will have to proxy the return in the case of a tail call to a third-party vat. + + params @4 :Payload; + # The call parameters. `params.content` is a struct whose fields correspond to the parameters of + # the method. + + sendResultsTo :union { + # Where should the return message be sent? + + caller @5 :Void; + # Send the return message back to the caller (the usual). + + yourself @6 :Void; + # **(level 1)** + # + # Don't actually return the results to the sender. Instead, hold on to them and await + # instructions from the sender regarding what to do with them. In particular, the sender + # may subsequently send a `Return` for some other call (which the receiver had previously made + # to the sender) with `takeFromOtherQuestion` set. The results from this call are then used + # as the results of the other call. + # + # When `yourself` is used, the receiver must still send a `Return` for the call, but sets the + # field `resultsSentElsewhere` in that `Return` rather than including the results. + # + # This feature can be used to implement tail calls in which a call from Vat A to Vat B ends up + # returning the result of a call from Vat B back to Vat A. + # + # In particular, the most common use case for this feature is when Vat A makes a call to a + # promise in Vat B, and then that promise ends up resolving to a capability back in Vat A. + # Vat B must forward all the queued calls on that promise back to Vat A, but can set `yourself` + # in the calls so that the results need not pass back through Vat B. + # + # For example: + # - Alice, in Vat A, call foo() on Bob in Vat B. + # - Alice makes a pipelined call bar() on the promise returned by foo(). + # - Later on, Bob resolves the promise from foo() to point at Carol, who lives in Vat A (next + # to Alice). + # - Vat B dutifully forwards the bar() call to Carol. Let us call this forwarded call bar'(). + # Notice that bar() and bar'() are travelling in opposite directions on the same network + # link. + # - The `Call` for bar'() has `sendResultsTo` set to `yourself`, with the value being the + # question ID originally assigned to the bar() call. + # - Vat A receives bar'() and delivers it to Carol. + # - When bar'() returns, Vat A immediately takes the results and returns them from bar(). + # - Meanwhile, Vat A sends a `Return` for bar'() to Vat B, with `resultsSentElsewhere` set in + # place of results. + # - Vat A sends a `Finish` for that call to Vat B. + # - Vat B receives the `Return` for bar'() and sends a `Return` for bar(), with + # `receivedFromYourself` set in place of the results. + # - Vat B receives the `Finish` for bar() and sends a `Finish` to bar'(). + + thirdParty @7 :RecipientId; + # **(level 3)** + # + # The call's result should be returned to a different vat. The receiver (the callee) expects + # to receive an `Accept` message from the indicated vat, and should return the call's result + # to it, rather than to the sender of the `Call`. + # + # This operates much like `yourself`, above, except that Carol is in a separate Vat C. `Call` + # messages are sent from Vat A -> Vat B and Vat B -> Vat C. A `Return` message is sent from + # Vat B -> Vat A that contains `acceptFromThirdParty` in place of results. When Vat A sends + # an `Accept` to Vat C, it receives back a `Return` containing the call's actual result. Vat C + # also sends a `Return` to Vat B with `resultsSentElsewhere`. + } +} + +struct Return { + # **(level 0)** + # + # Message type sent from callee to caller indicating that the call has completed. + + answerId @0 :AnswerId; + # Equal to the QuestionId of the corresponding `Call` message. + + releaseParamCaps @1 :Bool = true; + # If true, all capabilities that were in the params should be considered released. The sender + # must not send separate `Release` messages for them. Level 0 implementations in particular + # should always set this true. This defaults true because if level 0 implementations forget to + # set it they'll never notice (just silently leak caps), but if level >=1 implementations forget + # to set it to false they'll quickly get errors. + + union { + results @2 :Payload; + # The result. + # + # For regular method calls, `results.content` points to the result struct. + # + # For a `Return` in response to an `Accept`, `results` contains a single capability (rather + # than a struct), and `results.content` is just a capability pointer with index 0. A `Finish` + # is still required in this case. + + exception @3 :Exception; + # Indicates that the call failed and explains why. + + canceled @4 :Void; + # Indicates that the call was canceled due to the caller sending a Finish message + # before the call had completed. + + resultsSentElsewhere @5 :Void; + # This is set when returning from a `Call` that had `sendResultsTo` set to something other + # than `caller`. + + takeFromOtherQuestion @6 :QuestionId; + # The sender has also sent (before this message) a `Call` with the given question ID and with + # `sendResultsTo.yourself` set, and the results of that other call should be used as the + # results here. + + acceptFromThirdParty @7 :ThirdPartyCapId; + # **(level 3)** + # + # The caller should contact a third-party vat to pick up the results. An `Accept` message + # sent to the vat will return the result. This pairs with `Call.sendResultsTo.thirdParty`. + # It should only be used if the corresponding `Call` had `allowThirdPartyTailCall` set. + } +} + +struct Finish { + # **(level 0)** + # + # Message type sent from the caller to the callee to indicate: + # 1) The questionId will no longer be used in any messages sent by the callee (no further + # pipelined requests). + # 2) If the call has not returned yet, the caller no longer cares about the result. If nothing + # else cares about the result either (e.g. there are no other outstanding calls pipelined on + # the result of this one) then the callee may wish to immediately cancel the operation and + # send back a Return message with "canceled" set. However, implementations are not required + # to support premature cancellation -- instead, the implementation may wait until the call + # actually completes and send a normal `Return` message. + # + # TODO(someday): Should we separate (1) and implicitly releasing result capabilities? It would be + # possible and useful to notify the server that it doesn't need to keep around the response to + # service pipeline requests even though the caller still wants to receive it / hasn't yet + # finished processing it. It could also be useful to notify the server that it need not marshal + # the results because the caller doesn't want them anyway, even if the caller is still sending + # pipelined calls, although this seems less useful (just saving some bytes on the wire). + + questionId @0 :QuestionId; + # ID of the call whose result is to be released. + + releaseResultCaps @1 :Bool = true; + # If true, all capabilities that were in the results should be considered released. The sender + # must not send separate `Release` messages for them. Level 0 implementations in particular + # should always set this true. This defaults true because if level 0 implementations forget to + # set it they'll never notice (just silently leak caps), but if level >=1 implementations forget + # set it false they'll quickly get errors. +} + +# Level 1 message types ---------------------------------------------- + +struct Resolve { + # **(level 1)** + # + # Message type sent to indicate that a previously-sent promise has now been resolved to some other + # object (possibly another promise) -- or broken, or canceled. + # + # Keep in mind that it's possible for a `Resolve` to be sent to a level 0 implementation that + # doesn't implement it. For example, a method call or return might contain a capability in the + # payload. Normally this is fine even if the receiver is level 0, because they will implicitly + # release all such capabilities on return / finish. But if the cap happens to be a promise, then + # a follow-up `Resolve` may be sent regardless of this release. The level 0 receiver will reply + # with an `unimplemented` message, and the sender (of the `Resolve`) can respond to this as if the + # receiver had immediately released any capability to which the promise resolved. + # + # When implementing promise resolution, it's important to understand how embargos work and the + # tricky case of the Tribble 4-way race condition. See the comments for the Disembargo message, + # below. + + promiseId @0 :ExportId; + # The ID of the promise to be resolved. + # + # Unlike all other instances of `ExportId` sent from the exporter, the `Resolve` message does + # _not_ increase the reference count of `promiseId`. In fact, it is expected that the receiver + # will release the export soon after receiving `Resolve`, and the sender will not send this + # `ExportId` again until it has been released and recycled. + # + # When an export ID sent over the wire (e.g. in a `CapDescriptor`) is indicated to be a promise, + # this indicates that the sender will follow up at some point with a `Resolve` message. If the + # same `promiseId` is sent again before `Resolve`, still only one `Resolve` is sent. If the + # same ID is sent again later _after_ a `Resolve`, it can only be because the export's + # reference count hit zero in the meantime and the ID was re-assigned to a new export, therefore + # this later promise does _not_ correspond to the earlier `Resolve`. + # + # If a promise ID's reference count reaches zero before a `Resolve` is sent, the `Resolve` + # message may or may not still be sent (the `Resolve` may have already been in-flight when + # `Release` was sent, but if the `Release` is received before `Resolve` then there is no longer + # any reason to send a `Resolve`). Thus a `Resolve` may be received for a promise of which + # the receiver has no knowledge, because it already released it earlier. In this case, the + # receiver should simply release the capability to which the promise resolved. + + union { + cap @1 :CapDescriptor; + # The object to which the promise resolved. + # + # The sender promises that from this point forth, until `promiseId` is released, it shall + # simply forward all messages to the capability designated by `cap`. This is true even if + # `cap` itself happens to desigate another promise, and that other promise later resolves -- + # messages sent to `promiseId` shall still go to that other promise, not to its resolution. + # This is important in the case that the receiver of the `Resolve` ends up sending a + # `Disembargo` message towards `promiseId` in order to control message ordering -- that + # `Disembargo` really needs to reflect back to exactly the object designated by `cap` even + # if that object is itself a promise. + + exception @2 :Exception; + # Indicates that the promise was broken. + } +} + +struct Release { + # **(level 1)** + # + # Message type sent to indicate that the sender is done with the given capability and the receiver + # can free resources allocated to it. + + id @0 :ImportId; + # What to release. + + referenceCount @1 :UInt32; + # The amount by which to decrement the reference count. The export is only actually released + # when the reference count reaches zero. +} + +struct Disembargo { + # **(level 1)** + # + # Message sent to indicate that an embargo on a recently-resolved promise may now be lifted. + # + # Embargos are used to enforce E-order in the presence of promise resolution. That is, if an + # application makes two calls foo() and bar() on the same capability reference, in that order, + # the calls should be delivered in the order in which they were made. But if foo() is called + # on a promise, and that promise happens to resolve before bar() is called, then the two calls + # may travel different paths over the network, and thus could arrive in the wrong order. In + # this case, the call to `bar()` must be embargoed, and a `Disembargo` message must be sent along + # the same path as `foo()` to ensure that the `Disembargo` arrives after `foo()`. Once the + # `Disembargo` arrives, `bar()` can then be delivered. + # + # There are two particular cases where embargos are important. Consider object Alice, in Vat A, + # who holds a promise P, pointing towards Vat B, that eventually resolves to Carol. The two + # cases are: + # - Carol lives in Vat A, i.e. next to Alice. In this case, Vat A needs to send a `Disembargo` + # message that echos through Vat B and back, to ensure that all pipelined calls on the promise + # have been delivered. + # - Carol lives in a different Vat C. When the promise resolves, a three-party handoff occurs + # (see `Provide` and `Accept`, which constitute level 3 of the protocol). In this case, we + # piggyback on the state that has already been set up to handle the handoff: the `Accept` + # message (from Vat A to Vat C) is embargoed, as are all pipelined messages sent to it, while + # a `Disembargo` message is sent from Vat A through Vat B to Vat C. See `Accept.embargo` for + # an example. + # + # Note that in the case where Carol actually lives in Vat B (i.e., the same vat that the promise + # already pointed at), no embargo is needed, because the pipelined calls are delivered over the + # same path as the later direct calls. + # + # Keep in mind that promise resolution happens both in the form of Resolve messages as well as + # Return messages (which resolve PromisedAnswers). Embargos apply in both cases. + # + # An alternative strategy for enforcing E-order over promise resolution could be for Vat A to + # implement the embargo internally. When Vat A is notified of promise resolution, it could + # send a dummy no-op call to promise P and wait for it to complete. Until that call completes, + # all calls to the capability are queued locally. This strategy works, but is pessimistic: + # in the three-party case, it requires an A -> B -> C -> B -> A round trip before calls can start + # being delivered directly to from Vat A to Vat C. The `Disembargo` message allows latency to be + # reduced. (In the two-party loopback case, the `Disembargo` message is just a more explicit way + # of accomplishing the same thing as a no-op call, but isn't any faster.) + # + # *The Tribble 4-way Race Condition* + # + # Any implementation of promise resolution and embargos must be aware of what we call the + # "Tribble 4-way race condition", after Dean Tribble, who explained the problem in a lively + # Friam meeting. + # + # Embargos are designed to work in the case where a two-hop path is being shortened to one hop. + # But sometimes there are more hops. Imagine that Alice has a reference to a remote promise P1 + # that eventually resolves to _another_ remote promise P2 (in a third vat), which _at the same + # time_ happens to resolve to Bob (in a fourth vat). In this case, we're shortening from a 3-hop + # path (with four parties) to a 1-hop path (Alice -> Bob). + # + # Extending the embargo/disembargo protocol to be able to shorted multiple hops at once seems + # difficult. Instead, we make a rule that prevents this case from coming up: + # + # One a promise P has been resolved to a remove object reference R, then all further messages + # received addressed to P will be forwarded strictly to R. Even if it turns out later that R is + # itself a promise, and has resolved to some other object Q, messages sent to P will still be + # forwarded to R, not directly to Q (R will of course further forward the messages to Q). + # + # This rule does not cause a significant performance burden because once P has resolved to R, it + # is expected that people sending messages to P will shortly start sending them to R instead and + # drop P. P is at end-of-life anyway, so it doesn't matter if it ignores chances to further + # optimize its path. + + target @0 :MessageTarget; + # What is to be disembargoed. + + using EmbargoId = UInt32; + # Used in `senderLoopback` and `receiverLoopback`, below. + + context :union { + senderLoopback @1 :EmbargoId; + # The sender is requesting a disembargo on a promise that is known to resolve back to a + # capability hosted by the sender. As soon as the receiver has echoed back all pipelined calls + # on this promise, it will deliver the Disembargo back to the sender with `receiverLoopback` + # set to the same value as `senderLoopback`. This value is chosen by the sender, and since + # it is also consumed be the sender, the sender can use whatever strategy it wants to make sure + # the value is unambiguous. + # + # The receiver must verify that the target capability actually resolves back to the sender's + # vat. Otherwise, the sender has committed a protocol error and should be disconnected. + + receiverLoopback @2 :EmbargoId; + # The receiver previously sent a `senderLoopback` Disembargo towards a promise resolving to + # this capability, and that Disembargo is now being echoed back. + + accept @3 :Void; + # **(level 3)** + # + # The sender is requesting a disembargo on a promise that is known to resolve to a third-party + # capability that the sender is currently in the process of accepting (using `Accept`). + # The receiver of this `Disembargo` has an outstanding `Provide` on said capability. The + # receiver should now send a `Disembargo` with `provide` set to the question ID of that + # `Provide` message. + # + # See `Accept.embargo` for an example. + + provide @4 :QuestionId; + # **(level 3)** + # + # The sender is requesting a disembargo on a capability currently being provided to a third + # party. The question ID identifies the `Provide` message previously sent by the sender to + # this capability. On receipt, the receiver (the capability host) shall release the embargo + # on the `Accept` message that it has received from the third party. See `Accept.embargo` for + # an example. + } +} + +# Level 2 message types ---------------------------------------------- + +# See persistent.capnp. + +# Level 3 message types ---------------------------------------------- + +struct Provide { + # **(level 3)** + # + # Message type sent to indicate that the sender wishes to make a particular capability implemented + # by the receiver available to a third party for direct access (without the need for the third + # party to proxy through the sender). + # + # (In CapTP, `Provide` and `Accept` are methods of the global `NonceLocator` object exported by + # every vat. In Cap'n Proto, we bake this into the core protocol.) + + questionId @0 :QuestionId; + # Question ID to be held open until the recipient has received the capability. A result will be + # returned once the third party has successfully received the capability. The sender must at some + # point send a `Finish` message as with any other call, and that message can be used to cancel the + # whole operation. + + target @1 :MessageTarget; + # What is to be provided to the third party. + + recipient @2 :RecipientId; + # Identity of the third party that is expected to pick up the capability. +} + +struct Accept { + # **(level 3)** + # + # Message type sent to pick up a capability hosted by the receiving vat and provided by a third + # party. The third party previously designated the capability using `Provide`. + # + # This message is also used to pick up a redirected return -- see `Return.redirect`. + + questionId @0 :QuestionId; + # A new question ID identifying this accept message, which will eventually receive a Return + # message containing the provided capability (or the call result in the case of a redirected + # return). + + provision @1 :ProvisionId; + # Identifies the provided object to be picked up. + + embargo @2 :Bool; + # If true, this accept shall be temporarily embargoed. The resulting `Return` will not be sent, + # and any pipelined calls will not be delivered, until the embargo is released. The receiver + # (the capability host) will expect the provider (the vat that sent the `Provide` message) to + # eventually send a `Disembargo` message with the field `context.provide` set to the question ID + # of the original `Provide` message. At that point, the embargo is released and the queued + # messages are delivered. + # + # For example: + # - Alice, in Vat A, holds a promise P, which currently points toward Vat B. + # - Alice calls foo() on P. The `Call` message is sent to Vat B. + # - The promise P in Vat B ends up resolving to Carol, in Vat C. + # - Vat B sends a `Provide` message to Vat C, identifying Vat A as the recipient. + # - Vat B sends a `Resolve` message to Vat A, indicating that the promise has resolved to a + # `ThirdPartyCapId` identifying Carol in Vat C. + # - Vat A sends an `Accept` message to Vat C to pick up the capability. Since Vat A knows that + # it has an outstanding call to the promise, it sets `embargo` to `true` in the `Accept` + # message. + # - Vat A sends a `Disembargo` message to Vat B on promise P, with `context.accept` set. + # - Alice makes a call bar() to promise P, which is now pointing towards Vat C. Alice doesn't + # know anything about the mechanics of promise resolution happening under the hood, but she + # expects that bar() will be delivered after foo() because that is the order in which she + # initiated the calls. + # - Vat A sends the bar() call to Vat C, as a pipelined call on the result of the `Accept` (which + # hasn't returned yet, due to the embargo). Since calls to the newly-accepted capability + # are embargoed, Vat C does not deliver the call yet. + # - At some point, Vat B forwards the foo() call from the beginning of this example on to Vat C. + # - Vat B forwards the `Disembargo` from Vat A on to vat C. It sets `context.provide` to the + # question ID of the `Provide` message it had sent previously. + # - Vat C receives foo() before `Disembargo`, thus allowing it to correctly deliver foo() + # before delivering bar(). + # - Vat C receives `Disembargo` from Vat B. It can now send a `Return` for the `Accept` from + # Vat A, as well as deliver bar(). +} + +# Level 4 message types ---------------------------------------------- + +struct Join { + # **(level 4)** + # + # Message type sent to implement E.join(), which, given a number of capabilities that are + # expected to be equivalent, finds the underlying object upon which they all agree and forms a + # direct connection to it, skipping any proxies that may have been constructed by other vats + # while transmitting the capability. See: + # http://erights.org/elib/equality/index.html + # + # Note that this should only serve to bypass fully-transparent proxies -- proxies that were + # created merely for convenience, without any intention of hiding the underlying object. + # + # For example, say Bob holds two capabilities hosted by Alice and Carol, but he expects that both + # are simply proxies for a capability hosted elsewhere. He then issues a join request, which + # operates as follows: + # - Bob issues Join requests on both Alice and Carol. Each request contains a different piece + # of the JoinKey. + # - Alice is proxying a capability hosted by Dana, so forwards the request to Dana's cap. + # - Dana receives the first request and sees that the JoinKeyPart is one of two. She notes that + # she doesn't have the other part yet, so she records the request and responds with a + # JoinResult. + # - Alice relays the JoinAswer back to Bob. + # - Carol is also proxying a capability from Dana, and so forwards her Join request to Dana as + # well. + # - Dana receives Carol's request and notes that she now has both parts of a JoinKey. She + # combines them in order to form information needed to form a secure connection to Bob. She + # also responds with another JoinResult. + # - Bob receives the responses from Alice and Carol. He uses the returned JoinResults to + # determine how to connect to Dana and attempts to form the connection. Since Bob and Dana now + # agree on a secret key that neither Alice nor Carol ever saw, this connection can be made + # securely even if Alice or Carol is conspiring against the other. (If Alice and Carol are + # conspiring _together_, they can obviously reproduce the key, but this doesn't matter because + # the whole point of the join is to verify that Alice and Carol agree on what capability they + # are proxying.) + # + # If the two capabilities aren't actually proxies of the same object, then the join requests + # will come back with conflicting `hostId`s and the join will fail before attempting to form any + # connection. + + questionId @0 :QuestionId; + # Question ID used to respond to this Join. (Note that this ID only identifies one part of the + # request for one hop; each part has a different ID and relayed copies of the request have + # (probably) different IDs still.) + # + # The receiver will reply with a `Return` whose `results` is a JoinResult. This `JoinResult` + # is relayed from the joined object's host, possibly with transformation applied as needed + # by the network. + # + # Like any return, the result must be released using a `Finish`. However, this release + # should not occur until the joiner has either successfully connected to the joined object. + # Vats relaying a `Join` message similarly must not release the result they receive until the + # return they relayed back towards the joiner has itself been released. This allows the + # joined object's host to detect when the Join operation is canceled before completing -- if + # it receives a `Finish` for one of the join results before the joiner successfully + # connects. It can then free any resources it had allocated as part of the join. + + target @1 :MessageTarget; + # The capability to join. + + keyPart @2 :JoinKeyPart; + # A part of the join key. These combine to form the complete join key, which is used to establish + # a direct connection. + + # TODO(before implementing): Change this so that multiple parts can be sent in a single Join + # message, so that if multiple join parts are going to cross the same connection they can be sent + # together, so that the receive can potentially optimize its handling of them. In the case where + # all parts are bundled together, should the recipient be expected to simply return a cap, so + # that the caller can immediately start pipelining to it? +} + +# ======================================================================================== +# Common structures used in messages + +struct MessageTarget { + # The target of a `Call` or other messages that target a capability. + + union { + importedCap @0 :ImportId; + # This message is to a capability or promise previously imported by the caller (exported by + # the receiver). + + promisedAnswer @1 :PromisedAnswer; + # This message is to a capability that is expected to be returned by another call that has not + # yet been completed. + # + # At level 0, this is supported only for addressing the result of a previous `Bootstrap`, so + # that initial startup doesn't require a round trip. + } +} + +struct Payload { + # Represents some data structure that might contain capabilities. + + content @0 :AnyPointer; + # Some Cap'n Proto data structure. Capability pointers embedded in this structure index into + # `capTable`. + + capTable @1 :List(CapDescriptor); + # Descriptors corresponding to the cap pointers in `content`. +} + +struct CapDescriptor { + # **(level 1)** + # + # When an application-defined type contains an interface pointer, that pointer contains an index + # into the message's capability table -- i.e. the `capTable` part of the `Payload`. Each + # capability in the table is represented as a `CapDescriptor`. The runtime API should not reveal + # the CapDescriptor directly to the application, but should instead wrap it in some kind of + # callable object with methods corresponding to the interface that the capability implements. + # + # Keep in mind that `ExportIds` in a `CapDescriptor` are subject to reference counting. See the + # description of `ExportId`. + + union { + none @0 :Void; + # There is no capability here. This `CapDescriptor` should not appear in the payload content. + # A `none` CapDescriptor can be generated when an application inserts a capability into a + # message and then later changes its mind and removes it -- rewriting all of the other + # capability pointers may be hard, so instead a tombstone is left, similar to the way a removed + # struct or list instance is zeroed out of the message but the space is not reclaimed. + # Hopefully this is unusual. + + senderHosted @1 :ExportId; + # A capability newly exported by the sender. This is the ID of the new capability in the + # sender's export table (receiver's import table). + + senderPromise @2 :ExportId; + # A promise that the sender will resolve later. The sender will send exactly one Resolve + # message at a future point in time to replace this promise. Note that even if the same + # `senderPromise` is received multiple times, only one `Resolve` is sent to cover all of + # them. If `senderPromise` is released before the `Resolve` is sent, the sender (of this + # `CapDescriptor`) may choose not to send the `Resolve` at all. + + receiverHosted @3 :ImportId; + # A capability (or promise) previously exported by the receiver (imported by the sender). + + receiverAnswer @4 :PromisedAnswer; + # A capability expected to be returned in the results of a currently-outstanding call posed + # by the sender. + + thirdPartyHosted @5 :ThirdPartyCapDescriptor; + # **(level 3)** + # + # A capability that lives in neither the sender's nor the receiver's vat. The sender needs + # to form a direct connection to a third party to pick up the capability. + # + # Level 1 and 2 implementations that receive a `thirdPartyHosted` may simply send calls to its + # `vine` instead. + } +} + +struct PromisedAnswer { + # **(mostly level 1)** + # + # Specifies how to derive a promise from an unanswered question, by specifying the path of fields + # to follow from the root of the eventual result struct to get to the desired capability. Used + # to address method calls to a not-yet-returned capability or to pass such a capability as an + # input to some other method call. + # + # Level 0 implementations must support `PromisedAnswer` only for the case where the answer is + # to a `Bootstrap` message. In this case, `path` is always empty since `Bootstrap` always returns + # a raw capability. + + questionId @0 :QuestionId; + # ID of the question (in the sender's question table / receiver's answer table) whose answer is + # expected to contain the capability. + + transform @1 :List(Op); + # Operations / transformations to apply to the result in order to get the capability actually + # being addressed. E.g. if the result is a struct and you want to call a method on a capability + # pointed to by a field of the struct, you need a `getPointerField` op. + + struct Op { + union { + noop @0 :Void; + # Does nothing. This member is mostly defined so that we can make `Op` a union even + # though (as of this writing) only one real operation is defined. + + getPointerField @1 :UInt16; + # Get a pointer field within a struct. The number is an index into the pointer section, NOT + # a field ordinal, so that the receiver does not need to understand the schema. + + # TODO(someday): We could add: + # - For lists, the ability to address every member of the list, or a slice of the list, the + # result of which would be another list. This is useful for implementing the equivalent of + # a SQL table join (not to be confused with the `Join` message type). + # - Maybe some ability to test a union. + # - Probably not a good idea: the ability to specify an arbitrary script to run on the + # result. We could define a little stack-based language where `Op` specifies one + # "instruction" or transformation to apply. Although this is not a good idea + # (over-engineered), any narrower additions to `Op` should be designed as if this + # were the eventual goal. + } + } +} + +struct ThirdPartyCapDescriptor { + # **(level 3)** + # + # Identifies a capability in a third-party vat that the sender wants the receiver to pick up. + + id @0 :ThirdPartyCapId; + # Identifies the third-party host and the specific capability to accept from it. + + vineId @1 :ExportId; + # A proxy for the third-party object exported by the sender. In CapTP terminology this is called + # a "vine", because it is an indirect reference to the third-party object that snakes through the + # sender vat. This serves two purposes: + # + # * Level 1 and 2 implementations that don't understand how to connect to a third party may + # simply send calls to the vine. Such calls will be forwarded to the third-party by the + # sender. + # + # * Level 3 implementations must release the vine once they have successfully picked up the + # object from the third party. This ensures that the capability is not released by the sender + # prematurely. + # + # The sender will close the `Provide` request that it has sent to the third party as soon as + # it receives either a `Call` or a `Release` message directed at the vine. +} + +struct Exception { + # **(level 0)** + # + # Describes an arbitrary error that prevented an operation (e.g. a call) from completing. + # + # Cap'n Proto exceptions always indicate that something went wrong. In other words, in a fantasy + # world where everything always works as expected, no exceptions would ever be thrown. Clients + # should only ever catch exceptions as a means to implement fault-tolerance, where "fault" can + # mean: + # - Bugs. + # - Invalid input. + # - Configuration errors. + # - Network problems. + # - Insufficient resources. + # - Version skew (unimplemented functionality). + # - Other logistical problems. + # + # Exceptions should NOT be used to flag application-specific conditions that a client is expected + # to handle in an application-specific way. Put another way, in the Cap'n Proto world, + # "checked exceptions" (where an interface explicitly defines the exceptions it throws and + # clients are forced by the type system to handle those exceptions) do NOT make sense. + + reason @0 :Text; + # Human-readable failure description. + + type @3 :Type; + # The type of the error. The purpose of this enum is not to describe the error itself, but + # rather to describe how the client might want to respond to the error. + + enum Type { + failed @0; + # A generic problem occurred, and it is believed that if the operation were repeated without + # any change in the state of the world, the problem would occur again. + # + # A client might respond to this error by logging it for investigation by the developer and/or + # displaying it to the user. + + overloaded @1; + # The request was rejected due to a temporary lack of resources. + # + # Examples include: + # - There's not enough CPU time to keep up with incoming requests, so some are rejected. + # - The server ran out of RAM or disk space during the request. + # - The operation timed out (took significantly longer than it should have). + # + # A client might respond to this error by scheduling to retry the operation much later. The + # client should NOT retry again immediately since this would likely exacerbate the problem. + + disconnected @2; + # The method failed because a connection to some necessary capability was lost. + # + # Examples include: + # - The client introduced the server to a third-party capability, the connection to that third + # party was subsequently lost, and then the client requested that the server use the dead + # capability for something. + # - The client previously requested that the server obtain a capability from some third party. + # The server returned a capability to an object wrapping the third-party capability. Later, + # the server's connection to the third party was lost. + # - The capability has been revoked. Revocation does not necessarily mean that the client is + # no longer authorized to use the capability; it is often used simply as a way to force the + # client to repeat the setup process, perhaps to efficiently move them to a new back-end or + # get them to recognize some other change that has occurred. + # + # A client should normally respond to this error by releasing all capabilities it is currently + # holding related to the one it called and then re-creating them by restoring SturdyRefs and/or + # repeating the method calls used to create them originally. In other words, disconnect and + # start over. This should in turn cause the server to obtain a new copy of the capability that + # it lost, thus making everything work. + # + # If the client receives another `disconnencted` error in the process of rebuilding the + # capability and retrying the call, it should treat this as an `overloaded` error: the network + # is currently unreliable, possibly due to load or other temporary issues. + + unimplemented @3; + # The server doesn't implement the requested method. If there is some other method that the + # client could call (perhaps an older and/or slower interface), it should try that instead. + # Otherwise, this should be treated like `failed`. + } + + obsoleteIsCallersFault @1 :Bool; + # OBSOLETE. Ignore. + + obsoleteDurability @2 :UInt16; + # OBSOLETE. See `type` instead. +} + +# ======================================================================================== +# Network-specific Parameters +# +# Some parts of the Cap'n Proto RPC protocol are not specified here because different vat networks +# may wish to use different approaches to solving them. For example, on the public internet, you +# may want to authenticate vats using public-key cryptography, but on a local intranet with trusted +# infrastructure, you may be happy to authenticate based on network address only, or some other +# lightweight mechanism. +# +# To accommodate this, we specify several "parameter" types. Each type is defined here as an +# alias for `AnyPointer`, but a specific network will want to define a specific set of types to use. +# All vats in a vat network must agree on these parameters in order to be able to communicate. +# Inter-network communication can be accomplished through "gateways" that perform translation +# between the primitives used on each network; these gateways may need to be deeply stateful, +# depending on the translations they perform. +# +# For interaction over the global internet between parties with no other prior arrangement, a +# particular set of bindings for these types is defined elsewhere. (TODO(someday): Specify where +# these common definitions live.) +# +# Another common network type is the two-party network, in which one of the parties typically +# interacts with the outside world entirely through the other party. In such a connection between +# Alice and Bob, all objects that exist on Bob's other networks appear to Alice as if they were +# hosted by Bob himself, and similarly all objects on Alice's network (if she even has one) appear +# to Bob as if they were hosted by Alice. This network type is interesting because from the point +# of view of a simple application that communicates with only one other party via the two-party +# protocol, there are no three-party interactions at all, and joins are unusually simple to +# implement, so implementing at level 4 is barely more complicated than implementing at level 1. +# Moreover, if you pair an app implementing the two-party network with a container that implements +# some other network, the app can then participate on the container's network just as if it +# implemented that network directly. The types used by the two-party network are defined in +# `rpc-twoparty.capnp`. +# +# The things that we need to parameterize are: +# - How to store capabilities long-term without holding a connection open (mostly level 2). +# - How to authenticate vats in three-party introductions (level 3). +# - How to implement `Join` (level 4). +# +# Persistent references +# --------------------- +# +# **(mostly level 2)** +# +# We want to allow some capabilities to be stored long-term, even if a connection is lost and later +# recreated. ExportId is a short-term identifier that is specific to a connection, so it doesn't +# help here. We need a way to specify long-term identifiers, as well as a strategy for +# reconnecting to a referenced capability later. +# +# Three-party interactions +# ------------------------ +# +# **(level 3)** +# +# In cases where more than two vats are interacting, we have situations where VatA holds a +# capability hosted by VatB and wants to send that capability to VatC. This can be accomplished +# by VatA proxying requests on the new capability, but doing so has two big problems: +# - It's inefficient, requiring an extra network hop. +# - If VatC receives another capability to the same object from VatD, it is difficult for VatC to +# detect that the two capabilities are really the same and to implement the E "join" operation, +# which is necessary for certain four-or-more-party interactions, such as the escrow pattern. +# See: http://www.erights.org/elib/equality/grant-matcher/index.html +# +# Instead, we want a way for VatC to form a direct, authenticated connection to VatB. +# +# Join +# ---- +# +# **(level 4)** +# +# The `Join` message type and corresponding operation arranges for a direct connection to be formed +# between the joiner and the host of the joined object, and this connection must be authenticated. +# Thus, the details are network-dependent. + +using SturdyRef = AnyPointer; +# **(level 2)** +# +# Identifies a persisted capability that can be restored in the future. How exactly a SturdyRef +# is restored to a live object is specified along with the SturdyRef definition (i.e. not by +# rpc.capnp). +# +# Generally a SturdyRef needs to specify three things: +# - How to reach the vat that can restore the ref (e.g. a hostname or IP address). +# - How to authenticate the vat after connecting (e.g. a public key fingerprint). +# - The identity of a specific object hosted by the vat. Generally, this is an opaque pointer whose +# format is defined by the specific vat -- the client has no need to inspect the object ID. +# It is important that the objec ID be unguessable if the object is not public (and objects +# should almost never be public). +# +# The above are only suggestions. Some networks might work differently. For example, a private +# network might employ a special restorer service whose sole purpose is to restore SturdyRefs. +# In this case, the entire contents of SturdyRef might be opaque, because they are intended only +# to be forwarded to the restorer service. + +using ProvisionId = AnyPointer; +# **(level 3)** +# +# The information that must be sent in an `Accept` message to identify the object being accepted. +# +# In a network where each vat has a public/private key pair, this could simply be the public key +# fingerprint of the provider vat along with the question ID used in the `Provide` message sent from +# that provider. + +using RecipientId = AnyPointer; +# **(level 3)** +# +# The information that must be sent in a `Provide` message to identify the recipient of the +# capability. +# +# In a network where each vat has a public/private key pair, this could simply be the public key +# fingerprint of the recipient. (CapTP also calls for a nonce to identify the object. In our +# case, the `Provide` message's `questionId` can serve as the nonce.) + +using ThirdPartyCapId = AnyPointer; +# **(level 3)** +# +# The information needed to connect to a third party and accept a capability from it. +# +# In a network where each vat has a public/private key pair, this could be a combination of the +# third party's public key fingerprint, hints on how to connect to the third party (e.g. an IP +# address), and the question ID used in the corresponding `Provide` message sent to that third party +# (used to identify which capability to pick up). + +using JoinKeyPart = AnyPointer; +# **(level 4)** +# +# A piece of a secret key. One piece is sent along each path that is expected to lead to the same +# place. Once the pieces are combined, a direct connection may be formed between the sender and +# the receiver, bypassing any men-in-the-middle along the paths. See the `Join` message type. +# +# The motivation for Joins is discussed under "Supporting Equality" in the "Unibus" protocol +# sketch: http://www.erights.org/elib/distrib/captp/unibus.html +# +# In a network where each vat has a public/private key pair and each vat forms no more than one +# connection to each other vat, Joins will rarely -- perhaps never -- be needed, as objects never +# need to be transparently proxied and references to the same object sent over the same connection +# have the same export ID. Thus, a successful join requires only checking that the two objects +# come from the same connection and have the same ID, and then completes immediately. +# +# However, in networks where two vats may form more than one connection between each other, or +# where proxying of objects occurs, joins are necessary. +# +# Typically, each JoinKeyPart would include a fixed-length data value such that all value parts +# XOR'd together forms a shared secret that can be used to form an encrypted connection between +# the joiner and the joined object's host. Each JoinKeyPart should also include an indication of +# how many parts to expect and a hash of the shared secret (used to match up parts). + +using JoinResult = AnyPointer; +# **(level 4)** +# +# Information returned as the result to a `Join` message, needed by the joiner in order to form a +# direct connection to a joined object. This might simply be the address of the joined object's +# host vat, since the `JoinKey` has already been communicated so the two vats already have a shared +# secret to use to authenticate each other. +# +# The `JoinResult` should also contain information that can be used to detect when the Join +# requests ended up reaching different objects, so that this situation can be detected easily. +# This could be a simple matter of including a sequence number -- if the joiner receives two +# `JoinResult`s with sequence number 0, then they must have come from different objects and the +# whole join is a failure. + +# ======================================================================================== +# Network interface sketch +# +# The interfaces below are meant to be pseudo-code to illustrate how the details of a particular +# vat network might be abstracted away. They are written like Cap'n Proto interfaces, but in +# practice you'd probably define these interfaces manually in the target programming language. A +# Cap'n Proto RPC implementation should be able to use these interfaces without knowing the +# definitions of the various network-specific parameters defined above. + +# interface VatNetwork { +# # Represents a vat network, with the ability to connect to particular vats and receive +# # connections from vats. +# # +# # Note that methods returning a `Connection` may return a pre-existing `Connection`, and the +# # caller is expected to find and share state with existing users of the connection. +# +# # Level 0 features ----------------------------------------------- +# +# connect(vatId :VatId) :Connection; +# # Connect to the given vat. The transport should return a promise that does not +# # resolve until authentication has completed, but allows messages to be pipelined in before +# # that; the transport either queues these messages until authenticated, or sends them encrypted +# # such that only the authentic vat would be able to decrypt them. The latter approach avoids a +# # round trip for authentication. +# +# accept() :Connection; +# # Wait for the next incoming connection and return it. Only connections formed by +# # connect() are returned by this method. +# +# # Level 4 features ----------------------------------------------- +# +# newJoiner(count :UInt32) :NewJoinerResponse; +# # Prepare a new Join operation, which will eventually lead to forming a new direct connection +# # to the host of the joined capability. `count` is the number of capabilities to join. +# +# struct NewJoinerResponse { +# joinKeyParts :List(JoinKeyPart); +# # Key parts to send in Join messages to each capability. +# +# joiner :Joiner; +# # Used to establish the final connection. +# } +# +# interface Joiner { +# addJoinResult(result :JoinResult) :Void; +# # Add a JoinResult received in response to one of the `Join` messages. All `JoinResult`s +# # returned from all paths must be added before trying to connect. +# +# connect() :ConnectionAndProvisionId; +# # Try to form a connection to the joined capability's host, verifying that it has received +# # all of the JoinKeyParts. Once the connection is formed, the caller should send an `Accept` +# # message on it with the specified `ProvisionId` in order to receive the final capability. +# } +# +# acceptConnectionFromJoiner(parts :List(JoinKeyPart), paths :List(VatPath)) +# :ConnectionAndProvisionId; +# # Called on a joined capability's host to receive the connection from the joiner, once all +# # key parts have arrived. The caller should expect to receive an `Accept` message over the +# # connection with the given ProvisionId. +# } +# +# interface Connection { +# # Level 0 features ----------------------------------------------- +# +# send(message :Message) :Void; +# # Send the message. Returns successfully when the message (and all preceding messages) has +# # been acknowledged by the recipient. +# +# receive() :Message; +# # Receive the next message, and acknowledges receipt to the sender. Messages are received in +# # the order in which they are sent. +# +# # Level 3 features ----------------------------------------------- +# +# introduceTo(recipient :Connection) :IntroductionInfo; +# # Call before starting a three-way introduction, assuming a `Provide` message is to be sent on +# # this connection and a `ThirdPartyCapId` is to be sent to `recipient`. +# +# struct IntroductionInfo { +# sendToRecipient :ThirdPartyCapId; +# sendToTarget :RecipientId; +# } +# +# connectToIntroduced(capId :ThirdPartyCapId) :ConnectionAndProvisionId; +# # Given a ThirdPartyCapId received over this connection, connect to the third party. The +# # caller should then send an `Accept` message over the new connection. +# +# acceptIntroducedConnection(recipientId :RecipientId) :Connection; +# # Given a RecipientId received in a `Provide` message on this `Connection`, wait for the +# # recipient to connect, and return the connection formed. Usually, the first message received +# # on the new connection will be an `Accept` message. +# } +# +# struct ConnectionAndProvisionId { +# # **(level 3)** +# +# connection :Connection; +# # Connection on which to issue `Accept` message. +# +# provision :ProvisionId; +# # `ProvisionId` to send in the `Accept` message. +# } diff --git a/phonelibs/capnp-cpp/include/capnp/rpc.capnp.h b/phonelibs/capnp-cpp/include/capnp/rpc.capnp.h new file mode 100644 index 00000000000000..0a440397fc3b51 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc.capnp.h @@ -0,0 +1,4898 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: rpc.capnp + +#ifndef CAPNP_INCLUDED_b312981b2552a250_ +#define CAPNP_INCLUDED_b312981b2552a250_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(91b79f1f808db032); +CAPNP_DECLARE_SCHEMA(e94ccf8031176ec4); +CAPNP_DECLARE_SCHEMA(836a53ce789d4cd4); +CAPNP_DECLARE_SCHEMA(dae8b0f61aab5f99); +CAPNP_DECLARE_SCHEMA(9e19b28d3db3573a); +CAPNP_DECLARE_SCHEMA(d37d2eb2c2f80e63); +CAPNP_DECLARE_SCHEMA(bbc29655fa89086e); +CAPNP_DECLARE_SCHEMA(ad1a6c0d7dd07497); +CAPNP_DECLARE_SCHEMA(f964368b0fbd3711); +CAPNP_DECLARE_SCHEMA(d562b4df655bdd4d); +CAPNP_DECLARE_SCHEMA(9c6a046bfbc1ac5a); +CAPNP_DECLARE_SCHEMA(d4c9b56290554016); +CAPNP_DECLARE_SCHEMA(fbe1980490e001af); +CAPNP_DECLARE_SCHEMA(95bc14545813fbc1); +CAPNP_DECLARE_SCHEMA(9a0e61223d96743b); +CAPNP_DECLARE_SCHEMA(8523ddc40b86b8b0); +CAPNP_DECLARE_SCHEMA(d800b1d6cd6f1ca0); +CAPNP_DECLARE_SCHEMA(f316944415569081); +CAPNP_DECLARE_SCHEMA(d37007fde1f0027d); +CAPNP_DECLARE_SCHEMA(d625b7063acf691a); +CAPNP_DECLARE_SCHEMA(b28c96e23f4cbd58); +enum class Type_b28c96e23f4cbd58: uint16_t { + FAILED, + OVERLOADED, + DISCONNECTED, + UNIMPLEMENTED, +}; +CAPNP_DECLARE_ENUM(Type, b28c96e23f4cbd58); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace rpc { + +struct Message { + Message() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + UNIMPLEMENTED, + ABORT, + CALL, + RETURN, + FINISH, + RESOLVE, + RELEASE, + OBSOLETE_SAVE, + BOOTSTRAP, + OBSOLETE_DELETE, + PROVIDE, + ACCEPT, + JOIN, + DISEMBARGO, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(91b79f1f808db032, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Bootstrap { + Bootstrap() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e94ccf8031176ec4, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Call { + Call() = delete; + + class Reader; + class Builder; + class Pipeline; + struct SendResultsTo; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(836a53ce789d4cd4, 3, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Call::SendResultsTo { + SendResultsTo() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + CALLER, + YOURSELF, + THIRD_PARTY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(dae8b0f61aab5f99, 3, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Return { + Return() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + RESULTS, + EXCEPTION, + CANCELED, + RESULTS_SENT_ELSEWHERE, + TAKE_FROM_OTHER_QUESTION, + ACCEPT_FROM_THIRD_PARTY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9e19b28d3db3573a, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Finish { + Finish() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d37d2eb2c2f80e63, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Resolve { + Resolve() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + CAP, + EXCEPTION, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bbc29655fa89086e, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Release { + Release() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ad1a6c0d7dd07497, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Disembargo { + Disembargo() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Context; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f964368b0fbd3711, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Disembargo::Context { + Context() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + SENDER_LOOPBACK, + RECEIVER_LOOPBACK, + ACCEPT, + PROVIDE, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d562b4df655bdd4d, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Provide { + Provide() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9c6a046bfbc1ac5a, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Accept { + Accept() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d4c9b56290554016, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Join { + Join() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(fbe1980490e001af, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MessageTarget { + MessageTarget() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + IMPORTED_CAP, + PROMISED_ANSWER, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(95bc14545813fbc1, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Payload { + Payload() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9a0e61223d96743b, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CapDescriptor { + CapDescriptor() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + NONE, + SENDER_HOSTED, + SENDER_PROMISE, + RECEIVER_HOSTED, + RECEIVER_ANSWER, + THIRD_PARTY_HOSTED, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8523ddc40b86b8b0, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PromisedAnswer { + PromisedAnswer() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Op; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d800b1d6cd6f1ca0, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PromisedAnswer::Op { + Op() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + NOOP, + GET_POINTER_FIELD, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f316944415569081, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ThirdPartyCapDescriptor { + ThirdPartyCapDescriptor() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d37007fde1f0027d, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Exception { + Exception() = delete; + + class Reader; + class Builder; + class Pipeline; + typedef ::capnp::schemas::Type_b28c96e23f4cbd58 Type; + + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d625b7063acf691a, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class Message::Reader { +public: + typedef Message Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isUnimplemented() const; + inline bool hasUnimplemented() const; + inline ::capnp::rpc::Message::Reader getUnimplemented() const; + + inline bool isAbort() const; + inline bool hasAbort() const; + inline ::capnp::rpc::Exception::Reader getAbort() const; + + inline bool isCall() const; + inline bool hasCall() const; + inline ::capnp::rpc::Call::Reader getCall() const; + + inline bool isReturn() const; + inline bool hasReturn() const; + inline ::capnp::rpc::Return::Reader getReturn() const; + + inline bool isFinish() const; + inline bool hasFinish() const; + inline ::capnp::rpc::Finish::Reader getFinish() const; + + inline bool isResolve() const; + inline bool hasResolve() const; + inline ::capnp::rpc::Resolve::Reader getResolve() const; + + inline bool isRelease() const; + inline bool hasRelease() const; + inline ::capnp::rpc::Release::Reader getRelease() const; + + inline bool isObsoleteSave() const; + inline bool hasObsoleteSave() const; + inline ::capnp::AnyPointer::Reader getObsoleteSave() const; + + inline bool isBootstrap() const; + inline bool hasBootstrap() const; + inline ::capnp::rpc::Bootstrap::Reader getBootstrap() const; + + inline bool isObsoleteDelete() const; + inline bool hasObsoleteDelete() const; + inline ::capnp::AnyPointer::Reader getObsoleteDelete() const; + + inline bool isProvide() const; + inline bool hasProvide() const; + inline ::capnp::rpc::Provide::Reader getProvide() const; + + inline bool isAccept() const; + inline bool hasAccept() const; + inline ::capnp::rpc::Accept::Reader getAccept() const; + + inline bool isJoin() const; + inline bool hasJoin() const; + inline ::capnp::rpc::Join::Reader getJoin() const; + + inline bool isDisembargo() const; + inline bool hasDisembargo() const; + inline ::capnp::rpc::Disembargo::Reader getDisembargo() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Message::Builder { +public: + typedef Message Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isUnimplemented(); + inline bool hasUnimplemented(); + inline ::capnp::rpc::Message::Builder getUnimplemented(); + inline void setUnimplemented( ::capnp::rpc::Message::Reader value); + inline ::capnp::rpc::Message::Builder initUnimplemented(); + inline void adoptUnimplemented(::capnp::Orphan< ::capnp::rpc::Message>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Message> disownUnimplemented(); + + inline bool isAbort(); + inline bool hasAbort(); + inline ::capnp::rpc::Exception::Builder getAbort(); + inline void setAbort( ::capnp::rpc::Exception::Reader value); + inline ::capnp::rpc::Exception::Builder initAbort(); + inline void adoptAbort(::capnp::Orphan< ::capnp::rpc::Exception>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Exception> disownAbort(); + + inline bool isCall(); + inline bool hasCall(); + inline ::capnp::rpc::Call::Builder getCall(); + inline void setCall( ::capnp::rpc::Call::Reader value); + inline ::capnp::rpc::Call::Builder initCall(); + inline void adoptCall(::capnp::Orphan< ::capnp::rpc::Call>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Call> disownCall(); + + inline bool isReturn(); + inline bool hasReturn(); + inline ::capnp::rpc::Return::Builder getReturn(); + inline void setReturn( ::capnp::rpc::Return::Reader value); + inline ::capnp::rpc::Return::Builder initReturn(); + inline void adoptReturn(::capnp::Orphan< ::capnp::rpc::Return>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Return> disownReturn(); + + inline bool isFinish(); + inline bool hasFinish(); + inline ::capnp::rpc::Finish::Builder getFinish(); + inline void setFinish( ::capnp::rpc::Finish::Reader value); + inline ::capnp::rpc::Finish::Builder initFinish(); + inline void adoptFinish(::capnp::Orphan< ::capnp::rpc::Finish>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Finish> disownFinish(); + + inline bool isResolve(); + inline bool hasResolve(); + inline ::capnp::rpc::Resolve::Builder getResolve(); + inline void setResolve( ::capnp::rpc::Resolve::Reader value); + inline ::capnp::rpc::Resolve::Builder initResolve(); + inline void adoptResolve(::capnp::Orphan< ::capnp::rpc::Resolve>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Resolve> disownResolve(); + + inline bool isRelease(); + inline bool hasRelease(); + inline ::capnp::rpc::Release::Builder getRelease(); + inline void setRelease( ::capnp::rpc::Release::Reader value); + inline ::capnp::rpc::Release::Builder initRelease(); + inline void adoptRelease(::capnp::Orphan< ::capnp::rpc::Release>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Release> disownRelease(); + + inline bool isObsoleteSave(); + inline bool hasObsoleteSave(); + inline ::capnp::AnyPointer::Builder getObsoleteSave(); + inline ::capnp::AnyPointer::Builder initObsoleteSave(); + + inline bool isBootstrap(); + inline bool hasBootstrap(); + inline ::capnp::rpc::Bootstrap::Builder getBootstrap(); + inline void setBootstrap( ::capnp::rpc::Bootstrap::Reader value); + inline ::capnp::rpc::Bootstrap::Builder initBootstrap(); + inline void adoptBootstrap(::capnp::Orphan< ::capnp::rpc::Bootstrap>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Bootstrap> disownBootstrap(); + + inline bool isObsoleteDelete(); + inline bool hasObsoleteDelete(); + inline ::capnp::AnyPointer::Builder getObsoleteDelete(); + inline ::capnp::AnyPointer::Builder initObsoleteDelete(); + + inline bool isProvide(); + inline bool hasProvide(); + inline ::capnp::rpc::Provide::Builder getProvide(); + inline void setProvide( ::capnp::rpc::Provide::Reader value); + inline ::capnp::rpc::Provide::Builder initProvide(); + inline void adoptProvide(::capnp::Orphan< ::capnp::rpc::Provide>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Provide> disownProvide(); + + inline bool isAccept(); + inline bool hasAccept(); + inline ::capnp::rpc::Accept::Builder getAccept(); + inline void setAccept( ::capnp::rpc::Accept::Reader value); + inline ::capnp::rpc::Accept::Builder initAccept(); + inline void adoptAccept(::capnp::Orphan< ::capnp::rpc::Accept>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Accept> disownAccept(); + + inline bool isJoin(); + inline bool hasJoin(); + inline ::capnp::rpc::Join::Builder getJoin(); + inline void setJoin( ::capnp::rpc::Join::Reader value); + inline ::capnp::rpc::Join::Builder initJoin(); + inline void adoptJoin(::capnp::Orphan< ::capnp::rpc::Join>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Join> disownJoin(); + + inline bool isDisembargo(); + inline bool hasDisembargo(); + inline ::capnp::rpc::Disembargo::Builder getDisembargo(); + inline void setDisembargo( ::capnp::rpc::Disembargo::Reader value); + inline ::capnp::rpc::Disembargo::Builder initDisembargo(); + inline void adoptDisembargo(::capnp::Orphan< ::capnp::rpc::Disembargo>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Disembargo> disownDisembargo(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Message::Pipeline { +public: + typedef Message Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Bootstrap::Reader { +public: + typedef Bootstrap Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasDeprecatedObjectId() const; + inline ::capnp::AnyPointer::Reader getDeprecatedObjectId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Bootstrap::Builder { +public: + typedef Bootstrap Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasDeprecatedObjectId(); + inline ::capnp::AnyPointer::Builder getDeprecatedObjectId(); + inline ::capnp::AnyPointer::Builder initDeprecatedObjectId(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Bootstrap::Pipeline { +public: + typedef Bootstrap Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Call::Reader { +public: + typedef Call Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline ::uint64_t getInterfaceId() const; + + inline ::uint16_t getMethodId() const; + + inline bool hasParams() const; + inline ::capnp::rpc::Payload::Reader getParams() const; + + inline typename SendResultsTo::Reader getSendResultsTo() const; + + inline bool getAllowThirdPartyTailCall() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Call::Builder { +public: + typedef Call Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline ::uint64_t getInterfaceId(); + inline void setInterfaceId( ::uint64_t value); + + inline ::uint16_t getMethodId(); + inline void setMethodId( ::uint16_t value); + + inline bool hasParams(); + inline ::capnp::rpc::Payload::Builder getParams(); + inline void setParams( ::capnp::rpc::Payload::Reader value); + inline ::capnp::rpc::Payload::Builder initParams(); + inline void adoptParams(::capnp::Orphan< ::capnp::rpc::Payload>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Payload> disownParams(); + + inline typename SendResultsTo::Builder getSendResultsTo(); + inline typename SendResultsTo::Builder initSendResultsTo(); + + inline bool getAllowThirdPartyTailCall(); + inline void setAllowThirdPartyTailCall(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Call::Pipeline { +public: + typedef Call Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); + inline ::capnp::rpc::Payload::Pipeline getParams(); + inline typename SendResultsTo::Pipeline getSendResultsTo(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Call::SendResultsTo::Reader { +public: + typedef SendResultsTo Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isCaller() const; + inline ::capnp::Void getCaller() const; + + inline bool isYourself() const; + inline ::capnp::Void getYourself() const; + + inline bool isThirdParty() const; + inline bool hasThirdParty() const; + inline ::capnp::AnyPointer::Reader getThirdParty() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Call::SendResultsTo::Builder { +public: + typedef SendResultsTo Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isCaller(); + inline ::capnp::Void getCaller(); + inline void setCaller( ::capnp::Void value = ::capnp::VOID); + + inline bool isYourself(); + inline ::capnp::Void getYourself(); + inline void setYourself( ::capnp::Void value = ::capnp::VOID); + + inline bool isThirdParty(); + inline bool hasThirdParty(); + inline ::capnp::AnyPointer::Builder getThirdParty(); + inline ::capnp::AnyPointer::Builder initThirdParty(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Call::SendResultsTo::Pipeline { +public: + typedef SendResultsTo Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Return::Reader { +public: + typedef Return Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint32_t getAnswerId() const; + + inline bool getReleaseParamCaps() const; + + inline bool isResults() const; + inline bool hasResults() const; + inline ::capnp::rpc::Payload::Reader getResults() const; + + inline bool isException() const; + inline bool hasException() const; + inline ::capnp::rpc::Exception::Reader getException() const; + + inline bool isCanceled() const; + inline ::capnp::Void getCanceled() const; + + inline bool isResultsSentElsewhere() const; + inline ::capnp::Void getResultsSentElsewhere() const; + + inline bool isTakeFromOtherQuestion() const; + inline ::uint32_t getTakeFromOtherQuestion() const; + + inline bool isAcceptFromThirdParty() const; + inline bool hasAcceptFromThirdParty() const; + inline ::capnp::AnyPointer::Reader getAcceptFromThirdParty() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Return::Builder { +public: + typedef Return Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint32_t getAnswerId(); + inline void setAnswerId( ::uint32_t value); + + inline bool getReleaseParamCaps(); + inline void setReleaseParamCaps(bool value); + + inline bool isResults(); + inline bool hasResults(); + inline ::capnp::rpc::Payload::Builder getResults(); + inline void setResults( ::capnp::rpc::Payload::Reader value); + inline ::capnp::rpc::Payload::Builder initResults(); + inline void adoptResults(::capnp::Orphan< ::capnp::rpc::Payload>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Payload> disownResults(); + + inline bool isException(); + inline bool hasException(); + inline ::capnp::rpc::Exception::Builder getException(); + inline void setException( ::capnp::rpc::Exception::Reader value); + inline ::capnp::rpc::Exception::Builder initException(); + inline void adoptException(::capnp::Orphan< ::capnp::rpc::Exception>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Exception> disownException(); + + inline bool isCanceled(); + inline ::capnp::Void getCanceled(); + inline void setCanceled( ::capnp::Void value = ::capnp::VOID); + + inline bool isResultsSentElsewhere(); + inline ::capnp::Void getResultsSentElsewhere(); + inline void setResultsSentElsewhere( ::capnp::Void value = ::capnp::VOID); + + inline bool isTakeFromOtherQuestion(); + inline ::uint32_t getTakeFromOtherQuestion(); + inline void setTakeFromOtherQuestion( ::uint32_t value); + + inline bool isAcceptFromThirdParty(); + inline bool hasAcceptFromThirdParty(); + inline ::capnp::AnyPointer::Builder getAcceptFromThirdParty(); + inline ::capnp::AnyPointer::Builder initAcceptFromThirdParty(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Return::Pipeline { +public: + typedef Return Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Finish::Reader { +public: + typedef Finish Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool getReleaseResultCaps() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Finish::Builder { +public: + typedef Finish Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool getReleaseResultCaps(); + inline void setReleaseResultCaps(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Finish::Pipeline { +public: + typedef Finish Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Resolve::Reader { +public: + typedef Resolve Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint32_t getPromiseId() const; + + inline bool isCap() const; + inline bool hasCap() const; + inline ::capnp::rpc::CapDescriptor::Reader getCap() const; + + inline bool isException() const; + inline bool hasException() const; + inline ::capnp::rpc::Exception::Reader getException() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Resolve::Builder { +public: + typedef Resolve Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint32_t getPromiseId(); + inline void setPromiseId( ::uint32_t value); + + inline bool isCap(); + inline bool hasCap(); + inline ::capnp::rpc::CapDescriptor::Builder getCap(); + inline void setCap( ::capnp::rpc::CapDescriptor::Reader value); + inline ::capnp::rpc::CapDescriptor::Builder initCap(); + inline void adoptCap(::capnp::Orphan< ::capnp::rpc::CapDescriptor>&& value); + inline ::capnp::Orphan< ::capnp::rpc::CapDescriptor> disownCap(); + + inline bool isException(); + inline bool hasException(); + inline ::capnp::rpc::Exception::Builder getException(); + inline void setException( ::capnp::rpc::Exception::Reader value); + inline ::capnp::rpc::Exception::Builder initException(); + inline void adoptException(::capnp::Orphan< ::capnp::rpc::Exception>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Exception> disownException(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Resolve::Pipeline { +public: + typedef Resolve Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Release::Reader { +public: + typedef Release Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getId() const; + + inline ::uint32_t getReferenceCount() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Release::Builder { +public: + typedef Release Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getId(); + inline void setId( ::uint32_t value); + + inline ::uint32_t getReferenceCount(); + inline void setReferenceCount( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Release::Pipeline { +public: + typedef Release Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Disembargo::Reader { +public: + typedef Disembargo Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline typename Context::Reader getContext() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Disembargo::Builder { +public: + typedef Disembargo Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline typename Context::Builder getContext(); + inline typename Context::Builder initContext(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Disembargo::Pipeline { +public: + typedef Disembargo Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); + inline typename Context::Pipeline getContext(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Disembargo::Context::Reader { +public: + typedef Context Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isSenderLoopback() const; + inline ::uint32_t getSenderLoopback() const; + + inline bool isReceiverLoopback() const; + inline ::uint32_t getReceiverLoopback() const; + + inline bool isAccept() const; + inline ::capnp::Void getAccept() const; + + inline bool isProvide() const; + inline ::uint32_t getProvide() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Disembargo::Context::Builder { +public: + typedef Context Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isSenderLoopback(); + inline ::uint32_t getSenderLoopback(); + inline void setSenderLoopback( ::uint32_t value); + + inline bool isReceiverLoopback(); + inline ::uint32_t getReceiverLoopback(); + inline void setReceiverLoopback( ::uint32_t value); + + inline bool isAccept(); + inline ::capnp::Void getAccept(); + inline void setAccept( ::capnp::Void value = ::capnp::VOID); + + inline bool isProvide(); + inline ::uint32_t getProvide(); + inline void setProvide( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Disembargo::Context::Pipeline { +public: + typedef Context Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Provide::Reader { +public: + typedef Provide Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline bool hasRecipient() const; + inline ::capnp::AnyPointer::Reader getRecipient() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Provide::Builder { +public: + typedef Provide Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline bool hasRecipient(); + inline ::capnp::AnyPointer::Builder getRecipient(); + inline ::capnp::AnyPointer::Builder initRecipient(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Provide::Pipeline { +public: + typedef Provide Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Accept::Reader { +public: + typedef Accept Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasProvision() const; + inline ::capnp::AnyPointer::Reader getProvision() const; + + inline bool getEmbargo() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Accept::Builder { +public: + typedef Accept Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasProvision(); + inline ::capnp::AnyPointer::Builder getProvision(); + inline ::capnp::AnyPointer::Builder initProvision(); + + inline bool getEmbargo(); + inline void setEmbargo(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Accept::Pipeline { +public: + typedef Accept Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Join::Reader { +public: + typedef Join Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline bool hasKeyPart() const; + inline ::capnp::AnyPointer::Reader getKeyPart() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Join::Builder { +public: + typedef Join Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline bool hasKeyPart(); + inline ::capnp::AnyPointer::Builder getKeyPart(); + inline ::capnp::AnyPointer::Builder initKeyPart(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Join::Pipeline { +public: + typedef Join Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MessageTarget::Reader { +public: + typedef MessageTarget Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isImportedCap() const; + inline ::uint32_t getImportedCap() const; + + inline bool isPromisedAnswer() const; + inline bool hasPromisedAnswer() const; + inline ::capnp::rpc::PromisedAnswer::Reader getPromisedAnswer() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MessageTarget::Builder { +public: + typedef MessageTarget Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isImportedCap(); + inline ::uint32_t getImportedCap(); + inline void setImportedCap( ::uint32_t value); + + inline bool isPromisedAnswer(); + inline bool hasPromisedAnswer(); + inline ::capnp::rpc::PromisedAnswer::Builder getPromisedAnswer(); + inline void setPromisedAnswer( ::capnp::rpc::PromisedAnswer::Reader value); + inline ::capnp::rpc::PromisedAnswer::Builder initPromisedAnswer(); + inline void adoptPromisedAnswer(::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value); + inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> disownPromisedAnswer(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MessageTarget::Pipeline { +public: + typedef MessageTarget Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Payload::Reader { +public: + typedef Payload Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasContent() const; + inline ::capnp::AnyPointer::Reader getContent() const; + + inline bool hasCapTable() const; + inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader getCapTable() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Payload::Builder { +public: + typedef Payload Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasContent(); + inline ::capnp::AnyPointer::Builder getContent(); + inline ::capnp::AnyPointer::Builder initContent(); + + inline bool hasCapTable(); + inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder getCapTable(); + inline void setCapTable( ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader value); + inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder initCapTable(unsigned int size); + inline void adoptCapTable(::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>> disownCapTable(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Payload::Pipeline { +public: + typedef Payload Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CapDescriptor::Reader { +public: + typedef CapDescriptor Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isNone() const; + inline ::capnp::Void getNone() const; + + inline bool isSenderHosted() const; + inline ::uint32_t getSenderHosted() const; + + inline bool isSenderPromise() const; + inline ::uint32_t getSenderPromise() const; + + inline bool isReceiverHosted() const; + inline ::uint32_t getReceiverHosted() const; + + inline bool isReceiverAnswer() const; + inline bool hasReceiverAnswer() const; + inline ::capnp::rpc::PromisedAnswer::Reader getReceiverAnswer() const; + + inline bool isThirdPartyHosted() const; + inline bool hasThirdPartyHosted() const; + inline ::capnp::rpc::ThirdPartyCapDescriptor::Reader getThirdPartyHosted() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CapDescriptor::Builder { +public: + typedef CapDescriptor Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isNone(); + inline ::capnp::Void getNone(); + inline void setNone( ::capnp::Void value = ::capnp::VOID); + + inline bool isSenderHosted(); + inline ::uint32_t getSenderHosted(); + inline void setSenderHosted( ::uint32_t value); + + inline bool isSenderPromise(); + inline ::uint32_t getSenderPromise(); + inline void setSenderPromise( ::uint32_t value); + + inline bool isReceiverHosted(); + inline ::uint32_t getReceiverHosted(); + inline void setReceiverHosted( ::uint32_t value); + + inline bool isReceiverAnswer(); + inline bool hasReceiverAnswer(); + inline ::capnp::rpc::PromisedAnswer::Builder getReceiverAnswer(); + inline void setReceiverAnswer( ::capnp::rpc::PromisedAnswer::Reader value); + inline ::capnp::rpc::PromisedAnswer::Builder initReceiverAnswer(); + inline void adoptReceiverAnswer(::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value); + inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> disownReceiverAnswer(); + + inline bool isThirdPartyHosted(); + inline bool hasThirdPartyHosted(); + inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder getThirdPartyHosted(); + inline void setThirdPartyHosted( ::capnp::rpc::ThirdPartyCapDescriptor::Reader value); + inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder initThirdPartyHosted(); + inline void adoptThirdPartyHosted(::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor>&& value); + inline ::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor> disownThirdPartyHosted(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CapDescriptor::Pipeline { +public: + typedef CapDescriptor Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PromisedAnswer::Reader { +public: + typedef PromisedAnswer Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTransform() const; + inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader getTransform() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PromisedAnswer::Builder { +public: + typedef PromisedAnswer Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTransform(); + inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder getTransform(); + inline void setTransform( ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader value); + inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder initTransform(unsigned int size); + inline void adoptTransform(::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>> disownTransform(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PromisedAnswer::Pipeline { +public: + typedef PromisedAnswer Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PromisedAnswer::Op::Reader { +public: + typedef Op Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isNoop() const; + inline ::capnp::Void getNoop() const; + + inline bool isGetPointerField() const; + inline ::uint16_t getGetPointerField() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PromisedAnswer::Op::Builder { +public: + typedef Op Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isNoop(); + inline ::capnp::Void getNoop(); + inline void setNoop( ::capnp::Void value = ::capnp::VOID); + + inline bool isGetPointerField(); + inline ::uint16_t getGetPointerField(); + inline void setGetPointerField( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PromisedAnswer::Op::Pipeline { +public: + typedef Op Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ThirdPartyCapDescriptor::Reader { +public: + typedef ThirdPartyCapDescriptor Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasId() const; + inline ::capnp::AnyPointer::Reader getId() const; + + inline ::uint32_t getVineId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ThirdPartyCapDescriptor::Builder { +public: + typedef ThirdPartyCapDescriptor Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasId(); + inline ::capnp::AnyPointer::Builder getId(); + inline ::capnp::AnyPointer::Builder initId(); + + inline ::uint32_t getVineId(); + inline void setVineId( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ThirdPartyCapDescriptor::Pipeline { +public: + typedef ThirdPartyCapDescriptor Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Exception::Reader { +public: + typedef Exception Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasReason() const; + inline ::capnp::Text::Reader getReason() const; + + inline bool getObsoleteIsCallersFault() const; + + inline ::uint16_t getObsoleteDurability() const; + + inline ::capnp::rpc::Exception::Type getType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Exception::Builder { +public: + typedef Exception Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasReason(); + inline ::capnp::Text::Builder getReason(); + inline void setReason( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initReason(unsigned int size); + inline void adoptReason(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownReason(); + + inline bool getObsoleteIsCallersFault(); + inline void setObsoleteIsCallersFault(bool value); + + inline ::uint16_t getObsoleteDurability(); + inline void setObsoleteDurability( ::uint16_t value); + + inline ::capnp::rpc::Exception::Type getType(); + inline void setType( ::capnp::rpc::Exception::Type value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Exception::Pipeline { +public: + typedef Exception Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::rpc::Message::Which Message::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Message::Which Message::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Message::Reader::isUnimplemented() const { + return which() == Message::UNIMPLEMENTED; +} +inline bool Message::Builder::isUnimplemented() { + return which() == Message::UNIMPLEMENTED; +} +inline bool Message::Reader::hasUnimplemented() const { + if (which() != Message::UNIMPLEMENTED) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasUnimplemented() { + if (which() != Message::UNIMPLEMENTED) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Message::Reader Message::Reader::getUnimplemented() const { + KJ_IREQUIRE((which() == Message::UNIMPLEMENTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Message::Builder Message::Builder::getUnimplemented() { + KJ_IREQUIRE((which() == Message::UNIMPLEMENTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setUnimplemented( ::capnp::rpc::Message::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::UNIMPLEMENTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Message::Builder Message::Builder::initUnimplemented() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::UNIMPLEMENTED); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptUnimplemented( + ::capnp::Orphan< ::capnp::rpc::Message>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::UNIMPLEMENTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Message> Message::Builder::disownUnimplemented() { + KJ_IREQUIRE((which() == Message::UNIMPLEMENTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isAbort() const { + return which() == Message::ABORT; +} +inline bool Message::Builder::isAbort() { + return which() == Message::ABORT; +} +inline bool Message::Reader::hasAbort() const { + if (which() != Message::ABORT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasAbort() { + if (which() != Message::ABORT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Exception::Reader Message::Reader::getAbort() const { + KJ_IREQUIRE((which() == Message::ABORT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Exception::Builder Message::Builder::getAbort() { + KJ_IREQUIRE((which() == Message::ABORT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setAbort( ::capnp::rpc::Exception::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ABORT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Exception::Builder Message::Builder::initAbort() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ABORT); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptAbort( + ::capnp::Orphan< ::capnp::rpc::Exception>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ABORT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Exception> Message::Builder::disownAbort() { + KJ_IREQUIRE((which() == Message::ABORT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isCall() const { + return which() == Message::CALL; +} +inline bool Message::Builder::isCall() { + return which() == Message::CALL; +} +inline bool Message::Reader::hasCall() const { + if (which() != Message::CALL) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasCall() { + if (which() != Message::CALL) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Call::Reader Message::Reader::getCall() const { + KJ_IREQUIRE((which() == Message::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Call::Builder Message::Builder::getCall() { + KJ_IREQUIRE((which() == Message::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setCall( ::capnp::rpc::Call::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::CALL); + ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Call::Builder Message::Builder::initCall() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::CALL); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptCall( + ::capnp::Orphan< ::capnp::rpc::Call>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::CALL); + ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Call> Message::Builder::disownCall() { + KJ_IREQUIRE((which() == Message::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isReturn() const { + return which() == Message::RETURN; +} +inline bool Message::Builder::isReturn() { + return which() == Message::RETURN; +} +inline bool Message::Reader::hasReturn() const { + if (which() != Message::RETURN) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasReturn() { + if (which() != Message::RETURN) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Return::Reader Message::Reader::getReturn() const { + KJ_IREQUIRE((which() == Message::RETURN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Return::Builder Message::Builder::getReturn() { + KJ_IREQUIRE((which() == Message::RETURN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setReturn( ::capnp::rpc::Return::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RETURN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Return::Builder Message::Builder::initReturn() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RETURN); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptReturn( + ::capnp::Orphan< ::capnp::rpc::Return>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RETURN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Return> Message::Builder::disownReturn() { + KJ_IREQUIRE((which() == Message::RETURN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isFinish() const { + return which() == Message::FINISH; +} +inline bool Message::Builder::isFinish() { + return which() == Message::FINISH; +} +inline bool Message::Reader::hasFinish() const { + if (which() != Message::FINISH) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasFinish() { + if (which() != Message::FINISH) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Finish::Reader Message::Reader::getFinish() const { + KJ_IREQUIRE((which() == Message::FINISH), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Finish::Builder Message::Builder::getFinish() { + KJ_IREQUIRE((which() == Message::FINISH), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setFinish( ::capnp::rpc::Finish::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::FINISH); + ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Finish::Builder Message::Builder::initFinish() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::FINISH); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptFinish( + ::capnp::Orphan< ::capnp::rpc::Finish>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::FINISH); + ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Finish> Message::Builder::disownFinish() { + KJ_IREQUIRE((which() == Message::FINISH), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isResolve() const { + return which() == Message::RESOLVE; +} +inline bool Message::Builder::isResolve() { + return which() == Message::RESOLVE; +} +inline bool Message::Reader::hasResolve() const { + if (which() != Message::RESOLVE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasResolve() { + if (which() != Message::RESOLVE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Resolve::Reader Message::Reader::getResolve() const { + KJ_IREQUIRE((which() == Message::RESOLVE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Resolve::Builder Message::Builder::getResolve() { + KJ_IREQUIRE((which() == Message::RESOLVE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setResolve( ::capnp::rpc::Resolve::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RESOLVE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Resolve::Builder Message::Builder::initResolve() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RESOLVE); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptResolve( + ::capnp::Orphan< ::capnp::rpc::Resolve>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RESOLVE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Resolve> Message::Builder::disownResolve() { + KJ_IREQUIRE((which() == Message::RESOLVE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isRelease() const { + return which() == Message::RELEASE; +} +inline bool Message::Builder::isRelease() { + return which() == Message::RELEASE; +} +inline bool Message::Reader::hasRelease() const { + if (which() != Message::RELEASE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasRelease() { + if (which() != Message::RELEASE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Release::Reader Message::Reader::getRelease() const { + KJ_IREQUIRE((which() == Message::RELEASE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Release::Builder Message::Builder::getRelease() { + KJ_IREQUIRE((which() == Message::RELEASE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setRelease( ::capnp::rpc::Release::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RELEASE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Release::Builder Message::Builder::initRelease() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RELEASE); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptRelease( + ::capnp::Orphan< ::capnp::rpc::Release>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RELEASE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Release> Message::Builder::disownRelease() { + KJ_IREQUIRE((which() == Message::RELEASE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isObsoleteSave() const { + return which() == Message::OBSOLETE_SAVE; +} +inline bool Message::Builder::isObsoleteSave() { + return which() == Message::OBSOLETE_SAVE; +} +inline bool Message::Reader::hasObsoleteSave() const { + if (which() != Message::OBSOLETE_SAVE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasObsoleteSave() { + if (which() != Message::OBSOLETE_SAVE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Message::Reader::getObsoleteSave() const { + KJ_IREQUIRE((which() == Message::OBSOLETE_SAVE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::getObsoleteSave() { + KJ_IREQUIRE((which() == Message::OBSOLETE_SAVE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::initObsoleteSave() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::OBSOLETE_SAVE); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Message::Reader::isBootstrap() const { + return which() == Message::BOOTSTRAP; +} +inline bool Message::Builder::isBootstrap() { + return which() == Message::BOOTSTRAP; +} +inline bool Message::Reader::hasBootstrap() const { + if (which() != Message::BOOTSTRAP) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasBootstrap() { + if (which() != Message::BOOTSTRAP) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Bootstrap::Reader Message::Reader::getBootstrap() const { + KJ_IREQUIRE((which() == Message::BOOTSTRAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Bootstrap::Builder Message::Builder::getBootstrap() { + KJ_IREQUIRE((which() == Message::BOOTSTRAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setBootstrap( ::capnp::rpc::Bootstrap::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::BOOTSTRAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Bootstrap::Builder Message::Builder::initBootstrap() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::BOOTSTRAP); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptBootstrap( + ::capnp::Orphan< ::capnp::rpc::Bootstrap>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::BOOTSTRAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Bootstrap> Message::Builder::disownBootstrap() { + KJ_IREQUIRE((which() == Message::BOOTSTRAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isObsoleteDelete() const { + return which() == Message::OBSOLETE_DELETE; +} +inline bool Message::Builder::isObsoleteDelete() { + return which() == Message::OBSOLETE_DELETE; +} +inline bool Message::Reader::hasObsoleteDelete() const { + if (which() != Message::OBSOLETE_DELETE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasObsoleteDelete() { + if (which() != Message::OBSOLETE_DELETE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Message::Reader::getObsoleteDelete() const { + KJ_IREQUIRE((which() == Message::OBSOLETE_DELETE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::getObsoleteDelete() { + KJ_IREQUIRE((which() == Message::OBSOLETE_DELETE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::initObsoleteDelete() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::OBSOLETE_DELETE); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Message::Reader::isProvide() const { + return which() == Message::PROVIDE; +} +inline bool Message::Builder::isProvide() { + return which() == Message::PROVIDE; +} +inline bool Message::Reader::hasProvide() const { + if (which() != Message::PROVIDE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasProvide() { + if (which() != Message::PROVIDE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Provide::Reader Message::Reader::getProvide() const { + KJ_IREQUIRE((which() == Message::PROVIDE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Provide::Builder Message::Builder::getProvide() { + KJ_IREQUIRE((which() == Message::PROVIDE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setProvide( ::capnp::rpc::Provide::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::PROVIDE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Provide::Builder Message::Builder::initProvide() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::PROVIDE); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptProvide( + ::capnp::Orphan< ::capnp::rpc::Provide>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::PROVIDE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Provide> Message::Builder::disownProvide() { + KJ_IREQUIRE((which() == Message::PROVIDE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isAccept() const { + return which() == Message::ACCEPT; +} +inline bool Message::Builder::isAccept() { + return which() == Message::ACCEPT; +} +inline bool Message::Reader::hasAccept() const { + if (which() != Message::ACCEPT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasAccept() { + if (which() != Message::ACCEPT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Accept::Reader Message::Reader::getAccept() const { + KJ_IREQUIRE((which() == Message::ACCEPT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Accept::Builder Message::Builder::getAccept() { + KJ_IREQUIRE((which() == Message::ACCEPT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setAccept( ::capnp::rpc::Accept::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ACCEPT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Accept::Builder Message::Builder::initAccept() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ACCEPT); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptAccept( + ::capnp::Orphan< ::capnp::rpc::Accept>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ACCEPT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Accept> Message::Builder::disownAccept() { + KJ_IREQUIRE((which() == Message::ACCEPT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isJoin() const { + return which() == Message::JOIN; +} +inline bool Message::Builder::isJoin() { + return which() == Message::JOIN; +} +inline bool Message::Reader::hasJoin() const { + if (which() != Message::JOIN) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasJoin() { + if (which() != Message::JOIN) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Join::Reader Message::Reader::getJoin() const { + KJ_IREQUIRE((which() == Message::JOIN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Join::Builder Message::Builder::getJoin() { + KJ_IREQUIRE((which() == Message::JOIN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setJoin( ::capnp::rpc::Join::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::JOIN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Join::Builder Message::Builder::initJoin() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::JOIN); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptJoin( + ::capnp::Orphan< ::capnp::rpc::Join>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::JOIN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Join> Message::Builder::disownJoin() { + KJ_IREQUIRE((which() == Message::JOIN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isDisembargo() const { + return which() == Message::DISEMBARGO; +} +inline bool Message::Builder::isDisembargo() { + return which() == Message::DISEMBARGO; +} +inline bool Message::Reader::hasDisembargo() const { + if (which() != Message::DISEMBARGO) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasDisembargo() { + if (which() != Message::DISEMBARGO) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Disembargo::Reader Message::Reader::getDisembargo() const { + KJ_IREQUIRE((which() == Message::DISEMBARGO), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Disembargo::Builder Message::Builder::getDisembargo() { + KJ_IREQUIRE((which() == Message::DISEMBARGO), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setDisembargo( ::capnp::rpc::Disembargo::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::DISEMBARGO); + ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Disembargo::Builder Message::Builder::initDisembargo() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::DISEMBARGO); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptDisembargo( + ::capnp::Orphan< ::capnp::rpc::Disembargo>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::DISEMBARGO); + ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Disembargo> Message::Builder::disownDisembargo() { + KJ_IREQUIRE((which() == Message::DISEMBARGO), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Bootstrap::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Bootstrap::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Bootstrap::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Bootstrap::Reader::hasDeprecatedObjectId() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Bootstrap::Builder::hasDeprecatedObjectId() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Bootstrap::Reader::getDeprecatedObjectId() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Bootstrap::Builder::getDeprecatedObjectId() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Bootstrap::Builder::initDeprecatedObjectId() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t Call::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Call::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Call::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Call::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Call::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Call::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Call::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Call::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Call::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Call::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Call::Reader::getInterfaceId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Call::Builder::getInterfaceId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setInterfaceId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Call::Reader::getMethodId() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Call::Builder::getMethodId() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setMethodId( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Call::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Payload::Reader Call::Reader::getParams() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Payload::Builder Call::Builder::getParams() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::Payload::Pipeline Call::Pipeline::getParams() { + return ::capnp::rpc::Payload::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Call::Builder::setParams( ::capnp::rpc::Payload::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Payload::Builder Call::Builder::initParams() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Call::Builder::adoptParams( + ::capnp::Orphan< ::capnp::rpc::Payload>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Payload> Call::Builder::disownParams() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline typename Call::SendResultsTo::Reader Call::Reader::getSendResultsTo() const { + return typename Call::SendResultsTo::Reader(_reader); +} +inline typename Call::SendResultsTo::Builder Call::Builder::getSendResultsTo() { + return typename Call::SendResultsTo::Builder(_builder); +} +#if !CAPNP_LITE +inline typename Call::SendResultsTo::Pipeline Call::Pipeline::getSendResultsTo() { + return typename Call::SendResultsTo::Pipeline(_typeless.noop()); +} +#endif // !CAPNP_LITE +inline typename Call::SendResultsTo::Builder Call::Builder::initSendResultsTo() { + _builder.setDataField< ::uint16_t>(::capnp::bounded<3>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<2>() * ::capnp::POINTERS).clear(); + return typename Call::SendResultsTo::Builder(_builder); +} +inline bool Call::Reader::getAllowThirdPartyTailCall() const { + return _reader.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} + +inline bool Call::Builder::getAllowThirdPartyTailCall() { + return _builder.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setAllowThirdPartyTailCall(bool value) { + _builder.setDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::rpc::Call::SendResultsTo::Which Call::SendResultsTo::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Call::SendResultsTo::Which Call::SendResultsTo::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline bool Call::SendResultsTo::Reader::isCaller() const { + return which() == Call::SendResultsTo::CALLER; +} +inline bool Call::SendResultsTo::Builder::isCaller() { + return which() == Call::SendResultsTo::CALLER; +} +inline ::capnp::Void Call::SendResultsTo::Reader::getCaller() const { + KJ_IREQUIRE((which() == Call::SendResultsTo::CALLER), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Call::SendResultsTo::Builder::getCaller() { + KJ_IREQUIRE((which() == Call::SendResultsTo::CALLER), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Call::SendResultsTo::Builder::setCaller( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Call::SendResultsTo::CALLER); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::SendResultsTo::Reader::isYourself() const { + return which() == Call::SendResultsTo::YOURSELF; +} +inline bool Call::SendResultsTo::Builder::isYourself() { + return which() == Call::SendResultsTo::YOURSELF; +} +inline ::capnp::Void Call::SendResultsTo::Reader::getYourself() const { + KJ_IREQUIRE((which() == Call::SendResultsTo::YOURSELF), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Call::SendResultsTo::Builder::getYourself() { + KJ_IREQUIRE((which() == Call::SendResultsTo::YOURSELF), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Call::SendResultsTo::Builder::setYourself( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Call::SendResultsTo::YOURSELF); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::SendResultsTo::Reader::isThirdParty() const { + return which() == Call::SendResultsTo::THIRD_PARTY; +} +inline bool Call::SendResultsTo::Builder::isThirdParty() { + return which() == Call::SendResultsTo::THIRD_PARTY; +} +inline bool Call::SendResultsTo::Reader::hasThirdParty() const { + if (which() != Call::SendResultsTo::THIRD_PARTY) return false; + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Call::SendResultsTo::Builder::hasThirdParty() { + if (which() != Call::SendResultsTo::THIRD_PARTY) return false; + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Call::SendResultsTo::Reader::getThirdParty() const { + KJ_IREQUIRE((which() == Call::SendResultsTo::THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Call::SendResultsTo::Builder::getThirdParty() { + KJ_IREQUIRE((which() == Call::SendResultsTo::THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Call::SendResultsTo::Builder::initThirdParty() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Call::SendResultsTo::THIRD_PARTY); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::capnp::rpc::Return::Which Return::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Return::Which Return::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Return::Reader::getAnswerId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Return::Builder::getAnswerId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setAnswerId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::getReleaseParamCaps() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} + +inline bool Return::Builder::getReleaseParamCaps() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} +inline void Return::Builder::setReleaseParamCaps(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value, true); +} + +inline bool Return::Reader::isResults() const { + return which() == Return::RESULTS; +} +inline bool Return::Builder::isResults() { + return which() == Return::RESULTS; +} +inline bool Return::Reader::hasResults() const { + if (which() != Return::RESULTS) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Return::Builder::hasResults() { + if (which() != Return::RESULTS) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Payload::Reader Return::Reader::getResults() const { + KJ_IREQUIRE((which() == Return::RESULTS), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Payload::Builder Return::Builder::getResults() { + KJ_IREQUIRE((which() == Return::RESULTS), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::setResults( ::capnp::rpc::Payload::Reader value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS); + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Payload::Builder Return::Builder::initResults() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::adoptResults( + ::capnp::Orphan< ::capnp::rpc::Payload>&& value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS); + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Payload> Return::Builder::disownResults() { + KJ_IREQUIRE((which() == Return::RESULTS), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Return::Reader::isException() const { + return which() == Return::EXCEPTION; +} +inline bool Return::Builder::isException() { + return which() == Return::EXCEPTION; +} +inline bool Return::Reader::hasException() const { + if (which() != Return::EXCEPTION) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Return::Builder::hasException() { + if (which() != Return::EXCEPTION) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Exception::Reader Return::Reader::getException() const { + KJ_IREQUIRE((which() == Return::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Exception::Builder Return::Builder::getException() { + KJ_IREQUIRE((which() == Return::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::setException( ::capnp::rpc::Exception::Reader value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Exception::Builder Return::Builder::initException() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::EXCEPTION); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::adoptException( + ::capnp::Orphan< ::capnp::rpc::Exception>&& value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Exception> Return::Builder::disownException() { + KJ_IREQUIRE((which() == Return::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Return::Reader::isCanceled() const { + return which() == Return::CANCELED; +} +inline bool Return::Builder::isCanceled() { + return which() == Return::CANCELED; +} +inline ::capnp::Void Return::Reader::getCanceled() const { + KJ_IREQUIRE((which() == Return::CANCELED), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Return::Builder::getCanceled() { + KJ_IREQUIRE((which() == Return::CANCELED), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setCanceled( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::CANCELED); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::isResultsSentElsewhere() const { + return which() == Return::RESULTS_SENT_ELSEWHERE; +} +inline bool Return::Builder::isResultsSentElsewhere() { + return which() == Return::RESULTS_SENT_ELSEWHERE; +} +inline ::capnp::Void Return::Reader::getResultsSentElsewhere() const { + KJ_IREQUIRE((which() == Return::RESULTS_SENT_ELSEWHERE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Return::Builder::getResultsSentElsewhere() { + KJ_IREQUIRE((which() == Return::RESULTS_SENT_ELSEWHERE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setResultsSentElsewhere( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS_SENT_ELSEWHERE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::isTakeFromOtherQuestion() const { + return which() == Return::TAKE_FROM_OTHER_QUESTION; +} +inline bool Return::Builder::isTakeFromOtherQuestion() { + return which() == Return::TAKE_FROM_OTHER_QUESTION; +} +inline ::uint32_t Return::Reader::getTakeFromOtherQuestion() const { + KJ_IREQUIRE((which() == Return::TAKE_FROM_OTHER_QUESTION), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Return::Builder::getTakeFromOtherQuestion() { + KJ_IREQUIRE((which() == Return::TAKE_FROM_OTHER_QUESTION), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setTakeFromOtherQuestion( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::TAKE_FROM_OTHER_QUESTION); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::isAcceptFromThirdParty() const { + return which() == Return::ACCEPT_FROM_THIRD_PARTY; +} +inline bool Return::Builder::isAcceptFromThirdParty() { + return which() == Return::ACCEPT_FROM_THIRD_PARTY; +} +inline bool Return::Reader::hasAcceptFromThirdParty() const { + if (which() != Return::ACCEPT_FROM_THIRD_PARTY) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Return::Builder::hasAcceptFromThirdParty() { + if (which() != Return::ACCEPT_FROM_THIRD_PARTY) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Return::Reader::getAcceptFromThirdParty() const { + KJ_IREQUIRE((which() == Return::ACCEPT_FROM_THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Return::Builder::getAcceptFromThirdParty() { + KJ_IREQUIRE((which() == Return::ACCEPT_FROM_THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Return::Builder::initAcceptFromThirdParty() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::ACCEPT_FROM_THIRD_PARTY); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t Finish::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Finish::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Finish::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Finish::Reader::getReleaseResultCaps() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} + +inline bool Finish::Builder::getReleaseResultCaps() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} +inline void Finish::Builder::setReleaseResultCaps(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value, true); +} + +inline ::capnp::rpc::Resolve::Which Resolve::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Resolve::Which Resolve::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Resolve::Reader::getPromiseId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Resolve::Builder::getPromiseId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Resolve::Builder::setPromiseId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Resolve::Reader::isCap() const { + return which() == Resolve::CAP; +} +inline bool Resolve::Builder::isCap() { + return which() == Resolve::CAP; +} +inline bool Resolve::Reader::hasCap() const { + if (which() != Resolve::CAP) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Resolve::Builder::hasCap() { + if (which() != Resolve::CAP) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::CapDescriptor::Reader Resolve::Reader::getCap() const { + KJ_IREQUIRE((which() == Resolve::CAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::CapDescriptor::Builder Resolve::Builder::getCap() { + KJ_IREQUIRE((which() == Resolve::CAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::setCap( ::capnp::rpc::CapDescriptor::Reader value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::CAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::CapDescriptor::Builder Resolve::Builder::initCap() { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::CAP); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::adoptCap( + ::capnp::Orphan< ::capnp::rpc::CapDescriptor>&& value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::CAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::CapDescriptor> Resolve::Builder::disownCap() { + KJ_IREQUIRE((which() == Resolve::CAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Resolve::Reader::isException() const { + return which() == Resolve::EXCEPTION; +} +inline bool Resolve::Builder::isException() { + return which() == Resolve::EXCEPTION; +} +inline bool Resolve::Reader::hasException() const { + if (which() != Resolve::EXCEPTION) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Resolve::Builder::hasException() { + if (which() != Resolve::EXCEPTION) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Exception::Reader Resolve::Reader::getException() const { + KJ_IREQUIRE((which() == Resolve::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Exception::Builder Resolve::Builder::getException() { + KJ_IREQUIRE((which() == Resolve::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::setException( ::capnp::rpc::Exception::Reader value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Exception::Builder Resolve::Builder::initException() { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::EXCEPTION); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::adoptException( + ::capnp::Orphan< ::capnp::rpc::Exception>&& value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Exception> Resolve::Builder::disownException() { + KJ_IREQUIRE((which() == Resolve::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Release::Reader::getId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Release::Builder::getId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Release::Builder::setId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Release::Reader::getReferenceCount() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Release::Builder::getReferenceCount() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Release::Builder::setReferenceCount( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Disembargo::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Disembargo::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Disembargo::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Disembargo::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Disembargo::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Disembargo::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Disembargo::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Disembargo::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline typename Disembargo::Context::Reader Disembargo::Reader::getContext() const { + return typename Disembargo::Context::Reader(_reader); +} +inline typename Disembargo::Context::Builder Disembargo::Builder::getContext() { + return typename Disembargo::Context::Builder(_builder); +} +#if !CAPNP_LITE +inline typename Disembargo::Context::Pipeline Disembargo::Pipeline::getContext() { + return typename Disembargo::Context::Pipeline(_typeless.noop()); +} +#endif // !CAPNP_LITE +inline typename Disembargo::Context::Builder Disembargo::Builder::initContext() { + _builder.setDataField< ::uint32_t>(::capnp::bounded<0>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Disembargo::Context::Builder(_builder); +} +inline ::capnp::rpc::Disembargo::Context::Which Disembargo::Context::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Disembargo::Context::Which Disembargo::Context::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline bool Disembargo::Context::Reader::isSenderLoopback() const { + return which() == Disembargo::Context::SENDER_LOOPBACK; +} +inline bool Disembargo::Context::Builder::isSenderLoopback() { + return which() == Disembargo::Context::SENDER_LOOPBACK; +} +inline ::uint32_t Disembargo::Context::Reader::getSenderLoopback() const { + KJ_IREQUIRE((which() == Disembargo::Context::SENDER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Disembargo::Context::Builder::getSenderLoopback() { + KJ_IREQUIRE((which() == Disembargo::Context::SENDER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setSenderLoopback( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::SENDER_LOOPBACK); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Context::Reader::isReceiverLoopback() const { + return which() == Disembargo::Context::RECEIVER_LOOPBACK; +} +inline bool Disembargo::Context::Builder::isReceiverLoopback() { + return which() == Disembargo::Context::RECEIVER_LOOPBACK; +} +inline ::uint32_t Disembargo::Context::Reader::getReceiverLoopback() const { + KJ_IREQUIRE((which() == Disembargo::Context::RECEIVER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Disembargo::Context::Builder::getReceiverLoopback() { + KJ_IREQUIRE((which() == Disembargo::Context::RECEIVER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setReceiverLoopback( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::RECEIVER_LOOPBACK); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Context::Reader::isAccept() const { + return which() == Disembargo::Context::ACCEPT; +} +inline bool Disembargo::Context::Builder::isAccept() { + return which() == Disembargo::Context::ACCEPT; +} +inline ::capnp::Void Disembargo::Context::Reader::getAccept() const { + KJ_IREQUIRE((which() == Disembargo::Context::ACCEPT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Disembargo::Context::Builder::getAccept() { + KJ_IREQUIRE((which() == Disembargo::Context::ACCEPT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setAccept( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::ACCEPT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Context::Reader::isProvide() const { + return which() == Disembargo::Context::PROVIDE; +} +inline bool Disembargo::Context::Builder::isProvide() { + return which() == Disembargo::Context::PROVIDE; +} +inline ::uint32_t Disembargo::Context::Reader::getProvide() const { + KJ_IREQUIRE((which() == Disembargo::Context::PROVIDE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Disembargo::Context::Builder::getProvide() { + KJ_IREQUIRE((which() == Disembargo::Context::PROVIDE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setProvide( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::PROVIDE); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Provide::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Provide::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Provide::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Provide::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Provide::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Provide::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Provide::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Provide::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Provide::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Provide::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Provide::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Provide::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Provide::Reader::hasRecipient() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Provide::Builder::hasRecipient() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Provide::Reader::getRecipient() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Provide::Builder::getRecipient() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Provide::Builder::initRecipient() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t Accept::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Accept::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Accept::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Accept::Reader::hasProvision() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Accept::Builder::hasProvision() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Accept::Reader::getProvision() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Accept::Builder::getProvision() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Accept::Builder::initProvision() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Accept::Reader::getEmbargo() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} + +inline bool Accept::Builder::getEmbargo() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} +inline void Accept::Builder::setEmbargo(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Join::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Join::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Join::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Join::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Join::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Join::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Join::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Join::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Join::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Join::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Join::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Join::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Join::Reader::hasKeyPart() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Join::Builder::hasKeyPart() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Join::Reader::getKeyPart() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Join::Builder::getKeyPart() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Join::Builder::initKeyPart() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::capnp::rpc::MessageTarget::Which MessageTarget::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::MessageTarget::Which MessageTarget::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline bool MessageTarget::Reader::isImportedCap() const { + return which() == MessageTarget::IMPORTED_CAP; +} +inline bool MessageTarget::Builder::isImportedCap() { + return which() == MessageTarget::IMPORTED_CAP; +} +inline ::uint32_t MessageTarget::Reader::getImportedCap() const { + KJ_IREQUIRE((which() == MessageTarget::IMPORTED_CAP), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MessageTarget::Builder::getImportedCap() { + KJ_IREQUIRE((which() == MessageTarget::IMPORTED_CAP), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void MessageTarget::Builder::setImportedCap( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::IMPORTED_CAP); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool MessageTarget::Reader::isPromisedAnswer() const { + return which() == MessageTarget::PROMISED_ANSWER; +} +inline bool MessageTarget::Builder::isPromisedAnswer() { + return which() == MessageTarget::PROMISED_ANSWER; +} +inline bool MessageTarget::Reader::hasPromisedAnswer() const { + if (which() != MessageTarget::PROMISED_ANSWER) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MessageTarget::Builder::hasPromisedAnswer() { + if (which() != MessageTarget::PROMISED_ANSWER) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::PromisedAnswer::Reader MessageTarget::Reader::getPromisedAnswer() const { + KJ_IREQUIRE((which() == MessageTarget::PROMISED_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::PromisedAnswer::Builder MessageTarget::Builder::getPromisedAnswer() { + KJ_IREQUIRE((which() == MessageTarget::PROMISED_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MessageTarget::Builder::setPromisedAnswer( ::capnp::rpc::PromisedAnswer::Reader value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::PROMISED_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::PromisedAnswer::Builder MessageTarget::Builder::initPromisedAnswer() { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::PROMISED_ANSWER); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MessageTarget::Builder::adoptPromisedAnswer( + ::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::PROMISED_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> MessageTarget::Builder::disownPromisedAnswer() { + KJ_IREQUIRE((which() == MessageTarget::PROMISED_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Payload::Reader::hasContent() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Payload::Builder::hasContent() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Payload::Reader::getContent() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Payload::Builder::getContent() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Payload::Builder::initContent() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Payload::Reader::hasCapTable() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Payload::Builder::hasCapTable() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader Payload::Reader::getCapTable() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder Payload::Builder::getCapTable() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Payload::Builder::setCapTable( ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder Payload::Builder::initCapTable(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Payload::Builder::adoptCapTable( + ::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>> Payload::Builder::disownCapTable() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::capnp::rpc::CapDescriptor::Which CapDescriptor::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::CapDescriptor::Which CapDescriptor::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool CapDescriptor::Reader::isNone() const { + return which() == CapDescriptor::NONE; +} +inline bool CapDescriptor::Builder::isNone() { + return which() == CapDescriptor::NONE; +} +inline ::capnp::Void CapDescriptor::Reader::getNone() const { + KJ_IREQUIRE((which() == CapDescriptor::NONE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void CapDescriptor::Builder::getNone() { + KJ_IREQUIRE((which() == CapDescriptor::NONE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setNone( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::NONE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isSenderHosted() const { + return which() == CapDescriptor::SENDER_HOSTED; +} +inline bool CapDescriptor::Builder::isSenderHosted() { + return which() == CapDescriptor::SENDER_HOSTED; +} +inline ::uint32_t CapDescriptor::Reader::getSenderHosted() const { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_HOSTED), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CapDescriptor::Builder::getSenderHosted() { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_HOSTED), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setSenderHosted( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::SENDER_HOSTED); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isSenderPromise() const { + return which() == CapDescriptor::SENDER_PROMISE; +} +inline bool CapDescriptor::Builder::isSenderPromise() { + return which() == CapDescriptor::SENDER_PROMISE; +} +inline ::uint32_t CapDescriptor::Reader::getSenderPromise() const { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_PROMISE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CapDescriptor::Builder::getSenderPromise() { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_PROMISE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setSenderPromise( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::SENDER_PROMISE); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isReceiverHosted() const { + return which() == CapDescriptor::RECEIVER_HOSTED; +} +inline bool CapDescriptor::Builder::isReceiverHosted() { + return which() == CapDescriptor::RECEIVER_HOSTED; +} +inline ::uint32_t CapDescriptor::Reader::getReceiverHosted() const { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_HOSTED), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CapDescriptor::Builder::getReceiverHosted() { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_HOSTED), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setReceiverHosted( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_HOSTED); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isReceiverAnswer() const { + return which() == CapDescriptor::RECEIVER_ANSWER; +} +inline bool CapDescriptor::Builder::isReceiverAnswer() { + return which() == CapDescriptor::RECEIVER_ANSWER; +} +inline bool CapDescriptor::Reader::hasReceiverAnswer() const { + if (which() != CapDescriptor::RECEIVER_ANSWER) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CapDescriptor::Builder::hasReceiverAnswer() { + if (which() != CapDescriptor::RECEIVER_ANSWER) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::PromisedAnswer::Reader CapDescriptor::Reader::getReceiverAnswer() const { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::PromisedAnswer::Builder CapDescriptor::Builder::getReceiverAnswer() { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::setReceiverAnswer( ::capnp::rpc::PromisedAnswer::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::PromisedAnswer::Builder CapDescriptor::Builder::initReceiverAnswer() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_ANSWER); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::adoptReceiverAnswer( + ::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> CapDescriptor::Builder::disownReceiverAnswer() { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool CapDescriptor::Reader::isThirdPartyHosted() const { + return which() == CapDescriptor::THIRD_PARTY_HOSTED; +} +inline bool CapDescriptor::Builder::isThirdPartyHosted() { + return which() == CapDescriptor::THIRD_PARTY_HOSTED; +} +inline bool CapDescriptor::Reader::hasThirdPartyHosted() const { + if (which() != CapDescriptor::THIRD_PARTY_HOSTED) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CapDescriptor::Builder::hasThirdPartyHosted() { + if (which() != CapDescriptor::THIRD_PARTY_HOSTED) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::ThirdPartyCapDescriptor::Reader CapDescriptor::Reader::getThirdPartyHosted() const { + KJ_IREQUIRE((which() == CapDescriptor::THIRD_PARTY_HOSTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder CapDescriptor::Builder::getThirdPartyHosted() { + KJ_IREQUIRE((which() == CapDescriptor::THIRD_PARTY_HOSTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::setThirdPartyHosted( ::capnp::rpc::ThirdPartyCapDescriptor::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::THIRD_PARTY_HOSTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder CapDescriptor::Builder::initThirdPartyHosted() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::THIRD_PARTY_HOSTED); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::adoptThirdPartyHosted( + ::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::THIRD_PARTY_HOSTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor> CapDescriptor::Builder::disownThirdPartyHosted() { + KJ_IREQUIRE((which() == CapDescriptor::THIRD_PARTY_HOSTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t PromisedAnswer::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PromisedAnswer::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void PromisedAnswer::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool PromisedAnswer::Reader::hasTransform() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PromisedAnswer::Builder::hasTransform() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader PromisedAnswer::Reader::getTransform() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder PromisedAnswer::Builder::getTransform() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PromisedAnswer::Builder::setTransform( ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder PromisedAnswer::Builder::initTransform(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void PromisedAnswer::Builder::adoptTransform( + ::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>> PromisedAnswer::Builder::disownTransform() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::rpc::PromisedAnswer::Op::Which PromisedAnswer::Op::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::PromisedAnswer::Op::Which PromisedAnswer::Op::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool PromisedAnswer::Op::Reader::isNoop() const { + return which() == PromisedAnswer::Op::NOOP; +} +inline bool PromisedAnswer::Op::Builder::isNoop() { + return which() == PromisedAnswer::Op::NOOP; +} +inline ::capnp::Void PromisedAnswer::Op::Reader::getNoop() const { + KJ_IREQUIRE((which() == PromisedAnswer::Op::NOOP), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void PromisedAnswer::Op::Builder::getNoop() { + KJ_IREQUIRE((which() == PromisedAnswer::Op::NOOP), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void PromisedAnswer::Op::Builder::setNoop( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, PromisedAnswer::Op::NOOP); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool PromisedAnswer::Op::Reader::isGetPointerField() const { + return which() == PromisedAnswer::Op::GET_POINTER_FIELD; +} +inline bool PromisedAnswer::Op::Builder::isGetPointerField() { + return which() == PromisedAnswer::Op::GET_POINTER_FIELD; +} +inline ::uint16_t PromisedAnswer::Op::Reader::getGetPointerField() const { + KJ_IREQUIRE((which() == PromisedAnswer::Op::GET_POINTER_FIELD), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t PromisedAnswer::Op::Builder::getGetPointerField() { + KJ_IREQUIRE((which() == PromisedAnswer::Op::GET_POINTER_FIELD), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void PromisedAnswer::Op::Builder::setGetPointerField( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, PromisedAnswer::Op::GET_POINTER_FIELD); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool ThirdPartyCapDescriptor::Reader::hasId() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool ThirdPartyCapDescriptor::Builder::hasId() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader ThirdPartyCapDescriptor::Reader::getId() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder ThirdPartyCapDescriptor::Builder::getId() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder ThirdPartyCapDescriptor::Builder::initId() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t ThirdPartyCapDescriptor::Reader::getVineId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t ThirdPartyCapDescriptor::Builder::getVineId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void ThirdPartyCapDescriptor::Builder::setVineId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Exception::Reader::hasReason() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Exception::Builder::hasReason() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Exception::Reader::getReason() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Exception::Builder::getReason() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Exception::Builder::setReason( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Exception::Builder::initReason(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Exception::Builder::adoptReason( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Exception::Builder::disownReason() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Exception::Reader::getObsoleteIsCallersFault() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Exception::Builder::getObsoleteIsCallersFault() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Exception::Builder::setObsoleteIsCallersFault(bool value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Exception::Reader::getObsoleteDurability() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Exception::Builder::getObsoleteDurability() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Exception::Builder::setObsoleteDurability( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::rpc::Exception::Type Exception::Reader::getType() const { + return _reader.getDataField< ::capnp::rpc::Exception::Type>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::capnp::rpc::Exception::Type Exception::Builder::getType() { + return _builder.getDataField< ::capnp::rpc::Exception::Type>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Exception::Builder::setType( ::capnp::rpc::Exception::Type value) { + _builder.setDataField< ::capnp::rpc::Exception::Type>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_b312981b2552a250_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc.h b/phonelibs/capnp-cpp/include/capnp/rpc.h new file mode 100644 index 00000000000000..d84ed982e78314 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc.h @@ -0,0 +1,537 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_RPC_H_ +#define CAPNP_RPC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "capability.h" +#include "rpc-prelude.h" + +namespace capnp { + +template +class VatNetwork; +template +class SturdyRefRestorer; + +template +class BootstrapFactory: public _::BootstrapFactoryBase { + // Interface that constructs per-client bootstrap interfaces. Use this if you want each client + // who connects to see a different bootstrap interface based on their (authenticated) VatId. + // This allows an application to bootstrap off of the authentication performed at the VatNetwork + // level. (Typically VatId is some sort of public key.) + // + // This is only useful for multi-party networks. For TwoPartyVatNetwork, there's no reason to + // use a BootstrapFactory; just specify a single bootstrap capability in this case. + +public: + virtual Capability::Client createFor(typename VatId::Reader clientId) = 0; + // Create a bootstrap capability appropriate for exposing to the given client. VatNetwork will + // have authenticated the client VatId before this is called. + +private: + Capability::Client baseCreateFor(AnyStruct::Reader clientId) override; +}; + +template +class RpcSystem: public _::RpcSystemBase { + // Represents the RPC system, which is the portal to objects available on the network. + // + // The RPC implementation sits on top of an implementation of `VatNetwork`. The `VatNetwork` + // determines how to form connections between vats -- specifically, two-way, private, reliable, + // sequenced datagram connections. The RPC implementation determines how to use such connections + // to manage object references and make method calls. + // + // See `makeRpcServer()` and `makeRpcClient()` below for convenient syntax for setting up an + // `RpcSystem` given a `VatNetwork`. + // + // See `ez-rpc.h` for an even simpler interface for setting up RPC in a typical two-party + // client/server scenario. + +public: + template + RpcSystem( + VatNetwork& network, + kj::Maybe bootstrapInterface, + kj::Maybe::Client> gateway = nullptr); + + template + RpcSystem( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, + kj::Maybe::Client> gateway = nullptr); + + template + RpcSystem( + VatNetwork& network, + SturdyRefRestorer& restorer); + + RpcSystem(RpcSystem&& other) = default; + + Capability::Client bootstrap(typename VatId::Reader vatId); + // Connect to the given vat and return its bootstrap interface. + + Capability::Client restore(typename VatId::Reader hostId, AnyPointer::Reader objectId) + KJ_DEPRECATED("Please transition to using a bootstrap interface instead."); + // ** DEPRECATED ** + // + // Restores the given SturdyRef from the network and return the capability representing it. + // + // `hostId` identifies the host from which to request the ref, in the format specified by the + // `VatNetwork` in use. `objectId` is the object ID in whatever format is expected by said host. + // + // This method will be removed in a future version of Cap'n Proto. Instead, please transition + // to using bootstrap(), which is equivalent to calling restore() with a null `objectId`. + // You may emulate the old concept of object IDs by exporting a bootstrap interface which has + // methods that can be used to obtain other capabilities by ID. + + void setFlowLimit(size_t words); + // Sets the incoming call flow limit. If more than `words` worth of call messages have not yet + // received responses, the RpcSystem will not read further messages from the stream. This can be + // used as a crude way to prevent a resource exhaustion attack (or bug) in which a peer makes an + // excessive number of simultaneous calls that consume the receiver's RAM. + // + // There are some caveats. When over the flow limit, all messages are blocked, including returns. + // If the outstanding calls are themselves waiting on calls going in the opposite direction, the + // flow limit may prevent those calls from completing, leading to deadlock. However, a + // sufficiently high limit should make this unlikely. + // + // Note that a call's parameter size counts against the flow limit until the call returns, even + // if the recipient calls releaseParams() to free the parameter memory early. This is because + // releaseParams() may simply indicate that the parameters have been forwarded to another + // machine, but are still in-memory there. For illustration, say that Alice made a call to Bob + // who forwarded the call to Carol. Bob has imposed a flow limit on Alice. Alice's calls are + // being forwarded to Carol, so Bob never keeps the parameters in-memory for more than a brief + // period. However, the flow limit counts all calls that haven't returned, even if Bob has + // already freed the memory they consumed. You might argue that the right solution here is + // instead for Carol to impose her own flow limit on Bob. This has a serious problem, though: + // Bob might be forwarding requests to Carol on behalf of many different parties, not just Alice. + // If Alice can pump enough data to hit the Bob -> Carol flow limit, then those other parties + // will be disrupted. Thus, we can only really impose the limit on the Alice -> Bob link, which + // only affects Alice. We need that one flow limit to limit Alice's impact on the whole system, + // so it has to count all in-flight calls. + // + // In Sandstorm, flow limits are imposed by the supervisor on calls coming out of a grain, in + // order to prevent a grain from inundating the system with in-flight calls. In practice, the + // main time this happens is when a grain is pushing a large file download and doesn't implement + // proper cooperative flow control. +}; + +template +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface); +// Make an RPC server. Typical usage (e.g. in a main() function): +// +// MyEventLoop eventLoop; +// kj::WaitScope waitScope(eventLoop); +// MyNetwork network; +// MyMainInterface::Client bootstrap = makeMain(); +// auto server = makeRpcServer(network, bootstrap); +// kj::NEVER_DONE.wait(waitScope); // run forever +// +// See also ez-rpc.h, which has simpler instructions for the common case of a two-party +// client-server RPC connection. + +template , + typename ExternalRef = _::ExternalRefFromRealmGatewayClient> +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface, RealmGatewayClient gateway); +// Make an RPC server for a VatNetwork that resides in a different realm from the application. +// The given RealmGateway is used to translate SturdyRefs between the app's ("internal") format +// and the network's ("external") format. + +template +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory); +// Make an RPC server that can serve different bootstrap interfaces to different clients via a +// BootstrapInterface. + +template , + typename ExternalRef = _::ExternalRefFromRealmGatewayClient> +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, RealmGatewayClient gateway); +// Make an RPC server that can serve different bootstrap interfaces to different clients via a +// BootstrapInterface and communicates with a different realm than the application is in via a +// RealmGateway. + +template +RpcSystem makeRpcServer( + VatNetwork& network, + SturdyRefRestorer& restorer) + KJ_DEPRECATED("Please transition to using a bootstrap interface instead."); +// ** DEPRECATED ** +// +// Create an RPC server which exports multiple main interfaces by object ID. The `restorer` object +// can be used to look up objects by ID. +// +// Please transition to exporting only one interface, which is known as the "bootstrap" interface. +// For backwards-compatibility with old clients, continue to implement SturdyRefRestorer, but +// return the new bootstrap interface when the request object ID is null. When new clients connect +// and request the bootstrap interface, they will get that interface. Eventually, once all clients +// are updated to request only the bootstrap interface, stop implementing SturdyRefRestorer and +// switch to passing the bootstrap capability itself as the second parameter to `makeRpcServer()`. + +template +RpcSystem makeRpcClient( + VatNetwork& network); +// Make an RPC client. Typical usage (e.g. in a main() function): +// +// MyEventLoop eventLoop; +// kj::WaitScope waitScope(eventLoop); +// MyNetwork network; +// auto client = makeRpcClient(network); +// MyCapability::Client cap = client.restore(hostId, objId).castAs(); +// auto response = cap.fooRequest().send().wait(waitScope); +// handleMyResponse(response); +// +// See also ez-rpc.h, which has simpler instructions for the common case of a two-party +// client-server RPC connection. + +template , + typename ExternalRef = _::ExternalRefFromRealmGatewayClient> +RpcSystem makeRpcClient( + VatNetwork& network, + RealmGatewayClient gateway); +// Make an RPC client for a VatNetwork that resides in a different realm from the application. +// The given RealmGateway is used to translate SturdyRefs between the app's ("internal") format +// and the network's ("external") format. + +template +class SturdyRefRestorer: public _::SturdyRefRestorerBase { + // ** DEPRECATED ** + // + // In Cap'n Proto 0.4.x, applications could export multiple main interfaces identified by + // object IDs. The callback used to map object IDs to objects was `SturdyRefRestorer`, as we + // imagined this would eventually be used for restoring SturdyRefs as well. In practice, it was + // never used for real SturdyRefs, only for exporting singleton objects under well-known names. + // + // The new preferred strategy is to export only a _single_ such interface, called the + // "bootstrap interface". That interface can itself have methods for obtaining other objects, of + // course, but that is up to the app. `SturdyRefRestorer` exists for backwards-compatibility. + // + // Hint: Use SturdyRefRestorer to define a server that exports services under + // string names. + +public: + virtual Capability::Client restore(typename SturdyRefObjectId::Reader ref) + KJ_DEPRECATED( + "Please transition to using bootstrap interfaces instead of SturdyRefRestorer.") = 0; + // Restore the given object, returning a capability representing it. + +private: + Capability::Client baseRestore(AnyPointer::Reader ref) override final; +}; + +// ======================================================================================= +// VatNetwork + +class OutgoingRpcMessage { + // A message to be sent by a `VatNetwork`. + +public: + virtual AnyPointer::Builder getBody() = 0; + // Get the message body, which the caller may fill in any way it wants. (The standard RPC + // implementation initializes it as a Message as defined in rpc.capnp.) + + virtual void send() = 0; + // Send the message, or at least put it in a queue to be sent later. Note that the builder + // returned by `getBody()` remains valid at least until the `OutgoingRpcMessage` is destroyed. +}; + +class IncomingRpcMessage { + // A message received from a `VatNetwork`. + +public: + virtual AnyPointer::Reader getBody() = 0; + // Get the message body, to be interpreted by the caller. (The standard RPC implementation + // interprets it as a Message as defined in rpc.capnp.) +}; + +template +class VatNetwork: public _::VatNetworkBase { + // Cap'n Proto RPC operates between vats, where a "vat" is some sort of host of objects. + // Typically one Cap'n Proto process (in the Unix sense) is one vat. The RPC system is what + // allows calls between objects hosted in different vats. + // + // The RPC implementation sits on top of an implementation of `VatNetwork`. The `VatNetwork` + // determines how to form connections between vats -- specifically, two-way, private, reliable, + // sequenced datagram connections. The RPC implementation determines how to use such connections + // to manage object references and make method calls. + // + // The most common implementation of VatNetwork is TwoPartyVatNetwork (rpc-twoparty.h). Most + // simple client-server apps will want to use it. (You may even want to use the EZ RPC + // interfaces in `ez-rpc.h` and avoid all of this.) + // + // TODO(someday): Provide a standard implementation for the public internet. + +public: + class Connection; + + struct ConnectionAndProvisionId { + // Result of connecting to a vat introduced by another vat. + + kj::Own connection; + // Connection to the new vat. + + kj::Own firstMessage; + // An already-allocated `OutgoingRpcMessage` associated with `connection`. The RPC system will + // construct this as an `Accept` message and send it. + + Orphan provisionId; + // A `ProvisionId` already allocated inside `firstMessage`, which the RPC system will use to + // build the `Accept` message. + }; + + class Connection: public _::VatNetworkBase::Connection { + // A two-way RPC connection. + // + // This object may represent a connection that doesn't exist yet, but is expected to exist + // in the future. In this case, sent messages will automatically be queued and sent once the + // connection is ready, so that the caller doesn't need to know the difference. + + public: + // Level 0 features ---------------------------------------------- + + virtual typename VatId::Reader getPeerVatId() = 0; + // Returns the connected vat's authenticated VatId. It is the VatNetwork's responsibility to + // authenticate this, so that the caller can be assured that they are really talking to the + // identified vat and not an imposter. + + virtual kj::Own newOutgoingMessage(uint firstSegmentWordSize) override = 0; + // Allocate a new message to be sent on this connection. + // + // If `firstSegmentWordSize` is non-zero, it should be treated as a hint suggesting how large + // to make the first segment. This is entirely a hint and the connection may adjust it up or + // down. If it is zero, the connection should choose the size itself. + + virtual kj::Promise>> receiveIncomingMessage() override = 0; + // Wait for a message to be received and return it. If the read stream cleanly terminates, + // return null. If any other problem occurs, throw an exception. + + virtual kj::Promise shutdown() override KJ_WARN_UNUSED_RESULT = 0; + // Waits until all outgoing messages have been sent, then shuts down the outgoing stream. The + // returned promise resolves after shutdown is complete. + + private: + AnyStruct::Reader baseGetPeerVatId() override; + }; + + // Level 0 features ------------------------------------------------ + + virtual kj::Maybe> connect(typename VatId::Reader hostId) = 0; + // Connect to a VatId. Note that this method immediately returns a `Connection`, even + // if the network connection has not yet been established. Messages can be queued to this + // connection and will be delivered once it is open. The caller must attempt to read from the + // connection to verify that it actually succeeded; the read will fail if the connection + // couldn't be opened. Some network implementations may actually start sending messages before + // hearing back from the server at all, to avoid a round trip. + // + // Returns nullptr if `hostId` refers to the local host. + + virtual kj::Promise> accept() = 0; + // Wait for the next incoming connection and return it. + + // Level 4 features ------------------------------------------------ + // TODO(someday) + +private: + kj::Maybe> + baseConnect(AnyStruct::Reader hostId) override final; + kj::Promise> baseAccept() override final; +}; + +// ======================================================================================= +// *************************************************************************************** +// Inline implementation details start here +// *************************************************************************************** +// ======================================================================================= + +template +Capability::Client BootstrapFactory::baseCreateFor(AnyStruct::Reader clientId) { + return createFor(clientId.as()); +} + +template +kj::Maybe> + VatNetwork:: + baseConnect(AnyStruct::Reader ref) { + auto maybe = connect(ref.as()); + return maybe.map([](kj::Own& conn) -> kj::Own<_::VatNetworkBase::Connection> { + return kj::mv(conn); + }); +} + +template +kj::Promise> + VatNetwork::baseAccept() { + return accept().then( + [](kj::Own&& connection) -> kj::Own<_::VatNetworkBase::Connection> { + return kj::mv(connection); + }); +} + +template +AnyStruct::Reader VatNetwork< + SturdyRef, ProvisionId, RecipientId, ThirdPartyCapId, JoinResult>:: + Connection::baseGetPeerVatId() { + return getPeerVatId(); +} + +template +Capability::Client SturdyRefRestorer::baseRestore(AnyPointer::Reader ref) { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + return restore(ref.getAs()); +#pragma GCC diagnostic pop +} + +template +template +RpcSystem::RpcSystem( + VatNetwork& network, + kj::Maybe bootstrap, + kj::Maybe::Client> gateway) + : _::RpcSystemBase(network, kj::mv(bootstrap), kj::mv(gateway)) {} + +template +template +RpcSystem::RpcSystem( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, + kj::Maybe::Client> gateway) + : _::RpcSystemBase(network, bootstrapFactory, kj::mv(gateway)) {} + +template +template +RpcSystem::RpcSystem( + VatNetwork& network, + SturdyRefRestorer& restorer) + : _::RpcSystemBase(network, restorer) {} + +template +Capability::Client RpcSystem::bootstrap(typename VatId::Reader vatId) { + return baseBootstrap(_::PointerHelpers::getInternalReader(vatId)); +} + +template +Capability::Client RpcSystem::restore( + typename VatId::Reader hostId, AnyPointer::Reader objectId) { + return baseRestore(_::PointerHelpers::getInternalReader(hostId), objectId); +} + +template +inline void RpcSystem::setFlowLimit(size_t words) { + baseSetFlowLimit(words); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface) { + return RpcSystem(network, kj::mv(bootstrapInterface)); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface, RealmGatewayClient gateway) { + return RpcSystem(network, kj::mv(bootstrapInterface), + gateway.template castAs>()); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory) { + return RpcSystem(network, bootstrapFactory); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, RealmGatewayClient gateway) { + return RpcSystem(network, bootstrapFactory, gateway.template castAs>()); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + SturdyRefRestorer& restorer) { + return RpcSystem(network, restorer); +} + +template +RpcSystem makeRpcClient( + VatNetwork& network) { + return RpcSystem(network, nullptr); +} + +template +RpcSystem makeRpcClient( + VatNetwork& network, + RealmGatewayClient gateway) { + return RpcSystem(network, nullptr, gateway.template castAs>()); +} + +} // namespace capnp + +#endif // CAPNP_RPC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema-lite.h b/phonelibs/capnp-cpp/include/capnp/schema-lite.h new file mode 100644 index 00000000000000..58a8c14c05b73e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema-lite.h @@ -0,0 +1,48 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_LITE_H_ +#define CAPNP_SCHEMA_LITE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include "message.h" + +namespace capnp { + +template +inline schema::Node::Reader schemaProto() { + // Get the schema::Node for this type's schema. This function works even in lite mode. + return readMessageUnchecked(CapnpPrivate::encodedSchema()); +} + +template ::typeId> +inline schema::Node::Reader schemaProto() { + // Get the schema::Node for this type's schema. This function works even in lite mode. + return readMessageUnchecked(schemas::EnumInfo::encodedSchema()); +} + +} // namespace capnp + +#endif // CAPNP_SCHEMA_LITE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema-loader.h b/phonelibs/capnp-cpp/include/capnp/schema-loader.h new file mode 100644 index 00000000000000..0e34cba77fdbb8 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema-loader.h @@ -0,0 +1,173 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_LOADER_H_ +#define CAPNP_SCHEMA_LOADER_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "schema.h" +#include +#include + +namespace capnp { + +class SchemaLoader { + // Class which can be used to construct Schema objects from schema::Nodes as defined in + // schema.capnp. + // + // It is a bad idea to use this class on untrusted input with exceptions disabled -- you may + // be exposing yourself to denial-of-service attacks, as attackers can easily construct schemas + // that are subtly inconsistent in a way that causes exceptions to be thrown either by + // SchemaLoader or by the dynamic API when the schemas are subsequently used. If you enable and + // properly catch exceptions, you should be OK -- assuming no bugs in the Cap'n Proto + // implementation, of course. + +public: + class LazyLoadCallback { + public: + virtual void load(const SchemaLoader& loader, uint64_t id) const = 0; + // Request that the schema node with the given ID be loaded into the given SchemaLoader. If + // the callback is able to find a schema for this ID, it should invoke `loadOnce()` on + // `loader` to load it. If no such node exists, it should simply do nothing and return. + // + // The callback is allowed to load schema nodes other than the one requested, e.g. because it + // expects they will be needed soon. + // + // If the `SchemaLoader` is used from multiple threads, the callback must be thread-safe. + // In particular, it's possible for multiple threads to invoke `load()` with the same ID. + // If the callback performs a large amount of work to look up IDs, it should be sure to + // de-dup these requests. + }; + + SchemaLoader(); + + SchemaLoader(const LazyLoadCallback& callback); + // Construct a SchemaLoader which will invoke the given callback when a schema node is requested + // that isn't already loaded. + + ~SchemaLoader() noexcept(false); + KJ_DISALLOW_COPY(SchemaLoader); + + Schema get(uint64_t id, schema::Brand::Reader brand = schema::Brand::Reader(), + Schema scope = Schema()) const; + // Gets the schema for the given ID, throwing an exception if it isn't present. + // + // The returned schema may be invalidated if load() is called with a new schema for the same ID. + // In general, you should not call load() while a schema from this loader is in-use. + // + // `brand` and `scope` are used to determine brand bindings where relevant. `brand` gives + // parameter bindings for the target type's brand parameters that were specified at the reference + // site. `scope` specifies the scope in which the type ID appeared -- if `brand` itself contains + // parameter references or indicates that some parameters will be inherited, these will be + // interpreted within / inherited from `scope`. + + kj::Maybe tryGet(uint64_t id, schema::Brand::Reader bindings = schema::Brand::Reader(), + Schema scope = Schema()) const; + // Like get() but doesn't throw. + + Schema getUnbound(uint64_t id) const; + // Gets a special version of the schema in which all brand parameters are "unbound". This means + // that if you look up a type via the Schema API, and it resolves to a brand parameter, the + // returned Type's getBrandParameter() method will return info about that parameter. Otherwise, + // normally, all brand parameters that aren't otherwise bound are assumed to simply be + // "AnyPointer". + + Type getType(schema::Type::Reader type, Schema scope = Schema()) const; + // Convenience method which interprets a schema::Type to produce a Type object. Implemented in + // terms of get(). + + Schema load(const schema::Node::Reader& reader); + // Loads the given schema node. Validates the node and throws an exception if invalid. This + // makes a copy of the schema, so the object passed in can be destroyed after this returns. + // + // If the node has any dependencies which are not already loaded, they will be initialized as + // stubs -- empty schemas of whichever kind is expected. + // + // If another schema for the given reader has already been seen, the loader will inspect both + // schemas to determine which one is newer, and use that that one. If the two versions are + // found to be incompatible, an exception is thrown. If the two versions differ but are + // compatible and the loader cannot determine which is newer (e.g., the only changes are renames), + // the existing schema will be preferred. Note that in any case, the loader will end up keeping + // around copies of both schemas, so you shouldn't repeatedly reload schemas into the same loader. + // + // The following properties of the schema node are validated: + // - Struct size and preferred list encoding are valid and consistent. + // - Struct members are fields or unions. + // - Union members are fields. + // - Field offsets are in-bounds. + // - Ordinals and codeOrders are sequential starting from zero. + // - Values are of the right union case to match their types. + // + // You should assume anything not listed above is NOT validated. In particular, things that are + // not validated now, but could be in the future, include but are not limited to: + // - Names. + // - Annotation values. (This is hard because the annotation declaration is not always + // available.) + // - Content of default/constant values of pointer type. (Validating these would require knowing + // their schema, but even if the schemas are available at validation time, they could be + // updated by a subsequent load(), invalidating existing values. Instead, these values are + // validated at the time they are used, as usual for Cap'n Proto objects.) + // + // Also note that unknown types are not considered invalid. Instead, the dynamic API returns + // a DynamicValue with type UNKNOWN for these. + + Schema loadOnce(const schema::Node::Reader& reader) const; + // Like `load()` but does nothing if a schema with the same ID is already loaded. In contrast, + // `load()` would attempt to compare the schemas and take the newer one. `loadOnce()` is safe + // to call even while concurrently using schemas from this loader. It should be considered an + // error to call `loadOnce()` with two non-identical schemas that share the same ID, although + // this error may or may not actually be detected by the implementation. + + template + void loadCompiledTypeAndDependencies(); + // Load the schema for the given compiled-in type and all of its dependencies. + // + // If you want to be able to cast a DynamicValue built from this SchemaLoader to the compiled-in + // type using as(), you must call this method before constructing the DynamicValue. Otherwise, + // as() will throw an exception complaining about type mismatch. + + kj::Array getAllLoaded() const; + // Get a complete list of all loaded schema nodes. It is particularly useful to call this after + // loadCompiledTypeAndDependencies() in order to get a flat list of all of T's transitive + // dependencies. + +private: + class Validator; + class CompatibilityChecker; + class Impl; + class InitializerImpl; + class BrandedInitializerImpl; + kj::MutexGuarded> impl; + + void loadNative(const _::RawSchema* nativeSchema); +}; + +template +inline void SchemaLoader::loadCompiledTypeAndDependencies() { + loadNative(&_::rawSchema()); +} + +} // namespace capnp + +#endif // CAPNP_SCHEMA_LOADER_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema-parser.h b/phonelibs/capnp-cpp/include/capnp/schema-parser.h new file mode 100644 index 00000000000000..3322bbfbfbc77a --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema-parser.h @@ -0,0 +1,207 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_PARSER_H_ +#define CAPNP_SCHEMA_PARSER_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "schema-loader.h" +#include + +namespace capnp { + +class ParsedSchema; +class SchemaFile; + +class SchemaParser { + // Parses `.capnp` files to produce `Schema` objects. + // + // This class is thread-safe, hence all its methods are const. + +public: + SchemaParser(); + ~SchemaParser() noexcept(false); + + ParsedSchema parseDiskFile(kj::StringPtr displayName, kj::StringPtr diskPath, + kj::ArrayPtr importPath) const; + // Parse a file located on disk. Throws an exception if the file dosen't exist. + // + // Parameters: + // * `displayName`: The name that will appear in the file's schema node. (If the file has + // already been parsed, this will be ignored and the display name from the first time it was + // parsed will be kept.) + // * `diskPath`: The path to the file on disk. + // * `importPath`: Directories to search when resolving absolute imports within this file + // (imports that start with a `/`). Must remain valid until the SchemaParser is destroyed. + // (If the file has already been parsed, this will be ignored and the import path from the + // first time it was parsed will be kept.) + // + // This method is a shortcut, equivalent to: + // parser.parseFile(SchemaFile::newDiskFile(displayName, diskPath, importPath))`; + // + // This method throws an exception if any errors are encountered in the file or in anything the + // file depends on. Note that merely importing another file does not count as a dependency on + // anything in the imported file -- only the imported types which are actually used are + // "dependencies". + + ParsedSchema parseFile(kj::Own&& file) const; + // Advanced interface for parsing a file that may or may not be located in any global namespace. + // Most users will prefer `parseDiskFile()`. + // + // If the file has already been parsed (that is, a SchemaFile that compares equal to this one + // was parsed previously), the existing schema will be returned again. + // + // This method reports errors by calling SchemaFile::reportError() on the file where the error + // is located. If that call does not throw an exception, `parseFile()` may in fact return + // normally. In this case, the result is a best-effort attempt to compile the schema, but it + // may be invalid or corrupt, and using it for anything may cause exceptions to be thrown. + + template + inline void loadCompiledTypeAndDependencies() { + // See SchemaLoader::loadCompiledTypeAndDependencies(). + getLoader().loadCompiledTypeAndDependencies(); + } + +private: + struct Impl; + class ModuleImpl; + kj::Own impl; + mutable bool hadErrors = false; + + ModuleImpl& getModuleImpl(kj::Own&& file) const; + SchemaLoader& getLoader(); + + friend class ParsedSchema; +}; + +class ParsedSchema: public Schema { + // ParsedSchema is an extension of Schema which also has the ability to look up nested nodes + // by name. See `SchemaParser`. + +public: + inline ParsedSchema(): parser(nullptr) {} + + kj::Maybe findNested(kj::StringPtr name) const; + // Gets the nested node with the given name, or returns null if there is no such nested + // declaration. + + ParsedSchema getNested(kj::StringPtr name) const; + // Gets the nested node with the given name, or throws an exception if there is no such nested + // declaration. + +private: + inline ParsedSchema(Schema inner, const SchemaParser& parser): Schema(inner), parser(&parser) {} + + const SchemaParser* parser; + friend class SchemaParser; +}; + +// ======================================================================================= +// Advanced API + +class SchemaFile { + // Abstract interface representing a schema file. You can implement this yourself in order to + // gain more control over how the compiler resolves imports and reads files. For the + // common case of files on disk or other global filesystem-like namespaces, use + // `SchemaFile::newDiskFile()`. + +public: + class FileReader { + public: + virtual bool exists(kj::StringPtr path) const = 0; + virtual kj::Array read(kj::StringPtr path) const = 0; + }; + + class DiskFileReader final: public FileReader { + // Implementation of FileReader that uses the local disk. Files are read using mmap() if + // possible. + + public: + static const DiskFileReader instance; + + bool exists(kj::StringPtr path) const override; + kj::Array read(kj::StringPtr path) const override; + }; + + static kj::Own newDiskFile( + kj::StringPtr displayName, kj::StringPtr diskPath, + kj::ArrayPtr importPath, + const FileReader& fileReader = DiskFileReader::instance); + // Construct a SchemaFile representing a file on disk (or located in the filesystem-like + // namespace represented by `fileReader`). + // + // Parameters: + // * `displayName`: The name that will appear in the file's schema node. + // * `diskPath`: The path to the file on disk. + // * `importPath`: Directories to search when resolving absolute imports within this file + // (imports that start with a `/`). The array content must remain valid as long as the + // SchemaFile exists (which is at least as long as the SchemaParser that parses it exists). + // * `fileReader`: Allows you to use a filesystem other than the actual local disk. Although, + // if you find yourself using this, it may make more sense for you to implement SchemaFile + // yourself. + // + // The SchemaFile compares equal to any other SchemaFile that has exactly the same disk path, + // after canonicalization. + // + // The SchemaFile will throw an exception if any errors are reported. + + // ----------------------------------------------------------------- + // For more control, you can implement this interface. + + virtual kj::StringPtr getDisplayName() const = 0; + // Get the file's name, as it should appear in the schema. + + virtual kj::Array readContent() const = 0; + // Read the file's entire content and return it as a byte array. + + virtual kj::Maybe> import(kj::StringPtr path) const = 0; + // Resolve an import, relative to this file. + // + // `path` is exactly what appears between quotes after the `import` keyword in the source code. + // It is entirely up to the `SchemaFile` to decide how to map this to another file. Typically, + // a leading '/' means that the file is an "absolute" path and is searched for in some list of + // schema file repositories. On the other hand, a path that doesn't start with '/' is relative + // to the importing file. + + virtual bool operator==(const SchemaFile& other) const = 0; + virtual bool operator!=(const SchemaFile& other) const = 0; + virtual size_t hashCode() const = 0; + // Compare two SchemaFiles to see if they refer to the same underlying file. This is an + // optimization used to avoid the need to re-parse a file to check its ID. + + struct SourcePos { + uint byte; + uint line; + uint column; + }; + virtual void reportError(SourcePos start, SourcePos end, kj::StringPtr message) const = 0; + // Report that the file contains an error at the given interval. + +private: + class DiskSchemaFile; +}; + +} // namespace capnp + +#endif // CAPNP_SCHEMA_PARSER_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema.capnp b/phonelibs/capnp-cpp/include/capnp/schema.capnp new file mode 100644 index 00000000000000..4bef693f6cfd3e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema.capnp @@ -0,0 +1,498 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +using Cxx = import "/capnp/c++.capnp"; + +@0xa93fc509624c72d9; +$Cxx.namespace("capnp::schema"); + +using Id = UInt64; +# The globally-unique ID of a file, type, or annotation. + +struct Node { + id @0 :Id; + + displayName @1 :Text; + # Name to present to humans to identify this Node. You should not attempt to parse this. Its + # format could change. It is not guaranteed to be unique. + # + # (On Zooko's triangle, this is the node's nickname.) + + displayNamePrefixLength @2 :UInt32; + # If you want a shorter version of `displayName` (just naming this node, without its surrounding + # scope), chop off this many characters from the beginning of `displayName`. + + scopeId @3 :Id; + # ID of the lexical parent node. Typically, the scope node will have a NestedNode pointing back + # at this node, but robust code should avoid relying on this (and, in fact, group nodes are not + # listed in the outer struct's nestedNodes, since they are listed in the fields). `scopeId` is + # zero if the node has no parent, which is normally only the case with files, but should be + # allowed for any kind of node (in order to make runtime type generation easier). + + parameters @32 :List(Parameter); + # If this node is parameterized (generic), the list of parameters. Empty for non-generic types. + + isGeneric @33 :Bool; + # True if this node is generic, meaning that it or one of its parent scopes has a non-empty + # `parameters`. + + struct Parameter { + # Information about one of the node's parameters. + + name @0 :Text; + } + + nestedNodes @4 :List(NestedNode); + # List of nodes nested within this node, along with the names under which they were declared. + + struct NestedNode { + name @0 :Text; + # Unqualified symbol name. Unlike Node.displayName, this *can* be used programmatically. + # + # (On Zooko's triangle, this is the node's petname according to its parent scope.) + + id @1 :Id; + # ID of the nested node. Typically, the target node's scopeId points back to this node, but + # robust code should avoid relying on this. + } + + annotations @5 :List(Annotation); + # Annotations applied to this node. + + union { + # Info specific to each kind of node. + + file @6 :Void; + + struct :group { + dataWordCount @7 :UInt16; + # Size of the data section, in words. + + pointerCount @8 :UInt16; + # Size of the pointer section, in pointers (which are one word each). + + preferredListEncoding @9 :ElementSize; + # The preferred element size to use when encoding a list of this struct. If this is anything + # other than `inlineComposite` then the struct is one word or less in size and is a candidate + # for list packing optimization. + + isGroup @10 :Bool; + # If true, then this "struct" node is actually not an independent node, but merely represents + # some named union or group within a particular parent struct. This node's scopeId refers + # to the parent struct, which may itself be a union/group in yet another struct. + # + # All group nodes share the same dataWordCount and pointerCount as the top-level + # struct, and their fields live in the same ordinal and offset spaces as all other fields in + # the struct. + # + # Note that a named union is considered a special kind of group -- in fact, a named union + # is exactly equivalent to a group that contains nothing but an unnamed union. + + discriminantCount @11 :UInt16; + # Number of fields in this struct which are members of an anonymous union, and thus may + # overlap. If this is non-zero, then a 16-bit discriminant is present indicating which + # of the overlapping fields is active. This can never be 1 -- if it is non-zero, it must be + # two or more. + # + # Note that the fields of an unnamed union are considered fields of the scope containing the + # union -- an unnamed union is not its own group. So, a top-level struct may contain a + # non-zero discriminant count. Named unions, on the other hand, are equivalent to groups + # containing unnamed unions. So, a named union has its own independent schema node, with + # `isGroup` = true. + + discriminantOffset @12 :UInt32; + # If `discriminantCount` is non-zero, this is the offset of the union discriminant, in + # multiples of 16 bits. + + fields @13 :List(Field); + # Fields defined within this scope (either the struct's top-level fields, or the fields of + # a particular group; see `isGroup`). + # + # The fields are sorted by ordinal number, but note that because groups share the same + # ordinal space, the field's index in this list is not necessarily exactly its ordinal. + # On the other hand, the field's position in this list does remain the same even as the + # protocol evolves, since it is not possible to insert or remove an earlier ordinal. + # Therefore, for most use cases, if you want to identify a field by number, it may make the + # most sense to use the field's index in this list rather than its ordinal. + } + + enum :group { + enumerants@14 :List(Enumerant); + # Enumerants ordered by numeric value (ordinal). + } + + interface :group { + methods @15 :List(Method); + # Methods ordered by ordinal. + + superclasses @31 :List(Superclass); + # Superclasses of this interface. + } + + const :group { + type @16 :Type; + value @17 :Value; + } + + annotation :group { + type @18 :Type; + + targetsFile @19 :Bool; + targetsConst @20 :Bool; + targetsEnum @21 :Bool; + targetsEnumerant @22 :Bool; + targetsStruct @23 :Bool; + targetsField @24 :Bool; + targetsUnion @25 :Bool; + targetsGroup @26 :Bool; + targetsInterface @27 :Bool; + targetsMethod @28 :Bool; + targetsParam @29 :Bool; + targetsAnnotation @30 :Bool; + } + } +} + +struct Field { + # Schema for a field of a struct. + + name @0 :Text; + + codeOrder @1 :UInt16; + # Indicates where this member appeared in the code, relative to other members. + # Code ordering may have semantic relevance -- programmers tend to place related fields + # together. So, using code ordering makes sense in human-readable formats where ordering is + # otherwise irrelevant, like JSON. The values of codeOrder are tightly-packed, so the maximum + # value is count(members) - 1. Fields that are members of a union are only ordered relative to + # the other members of that union, so the maximum value there is count(union.members). + + annotations @2 :List(Annotation); + + const noDiscriminant :UInt16 = 0xffff; + + discriminantValue @3 :UInt16 = Field.noDiscriminant; + # If the field is in a union, this is the value which the union's discriminant should take when + # the field is active. If the field is not in a union, this is 0xffff. + + union { + slot :group { + # A regular, non-group, non-fixed-list field. + + offset @4 :UInt32; + # Offset, in units of the field's size, from the beginning of the section in which the field + # resides. E.g. for a UInt32 field, multiply this by 4 to get the byte offset from the + # beginning of the data section. + + type @5 :Type; + defaultValue @6 :Value; + + hadExplicitDefault @10 :Bool; + # Whether the default value was specified explicitly. Non-explicit default values are always + # zero or empty values. Usually, whether the default value was explicit shouldn't matter. + # The main use case for this flag is for structs representing method parameters: + # explicitly-defaulted parameters may be allowed to be omitted when calling the method. + } + + group :group { + # A group. + + typeId @7 :Id; + # The ID of the group's node. + } + } + + ordinal :union { + implicit @8 :Void; + explicit @9 :UInt16; + # The original ordinal number given to the field. You probably should NOT use this; if you need + # a numeric identifier for a field, use its position within the field array for its scope. + # The ordinal is given here mainly just so that the original schema text can be reproduced given + # the compiled version -- i.e. so that `capnp compile -ocapnp` can do its job. + } +} + +struct Enumerant { + # Schema for member of an enum. + + name @0 :Text; + + codeOrder @1 :UInt16; + # Specifies order in which the enumerants were declared in the code. + # Like Struct.Field.codeOrder. + + annotations @2 :List(Annotation); +} + +struct Superclass { + id @0 :Id; + brand @1 :Brand; +} + +struct Method { + # Schema for method of an interface. + + name @0 :Text; + + codeOrder @1 :UInt16; + # Specifies order in which the methods were declared in the code. + # Like Struct.Field.codeOrder. + + implicitParameters @7 :List(Node.Parameter); + # The parameters listed in [] (typically, type / generic parameters), whose bindings are intended + # to be inferred rather than specified explicitly, although not all languages support this. + + paramStructType @2 :Id; + # ID of the parameter struct type. If a named parameter list was specified in the method + # declaration (rather than a single struct parameter type) then a corresponding struct type is + # auto-generated. Such an auto-generated type will not be listed in the interface's + # `nestedNodes` and its `scopeId` will be zero -- it is completely detached from the namespace. + # (Awkwardly, it does of course inherit generic parameters from the method's scope, which makes + # this a situation where you can't just climb the scope chain to find where a particular + # generic parameter was introduced. Making the `scopeId` zero was a mistake.) + + paramBrand @5 :Brand; + # Brand of param struct type. + + resultStructType @3 :Id; + # ID of the return struct type; similar to `paramStructType`. + + resultBrand @6 :Brand; + # Brand of result struct type. + + annotations @4 :List(Annotation); +} + +struct Type { + # Represents a type expression. + + union { + # The ordinals intentionally match those of Value. + + void @0 :Void; + bool @1 :Void; + int8 @2 :Void; + int16 @3 :Void; + int32 @4 :Void; + int64 @5 :Void; + uint8 @6 :Void; + uint16 @7 :Void; + uint32 @8 :Void; + uint64 @9 :Void; + float32 @10 :Void; + float64 @11 :Void; + text @12 :Void; + data @13 :Void; + + list :group { + elementType @14 :Type; + } + + enum :group { + typeId @15 :Id; + brand @21 :Brand; + } + struct :group { + typeId @16 :Id; + brand @22 :Brand; + } + interface :group { + typeId @17 :Id; + brand @23 :Brand; + } + + anyPointer :union { + unconstrained :union { + # A regular AnyPointer. + # + # The name "unconstrained" means as opposed to constraining it to match a type parameter. + # In retrospect this name is probably a poor choice given that it may still be constrained + # to be a struct, list, or capability. + + anyKind @18 :Void; # truly AnyPointer + struct @25 :Void; # AnyStruct + list @26 :Void; # AnyList + capability @27 :Void; # Capability + } + + parameter :group { + # This is actually a reference to a type parameter defined within this scope. + + scopeId @19 :Id; + # ID of the generic type whose parameter we're referencing. This should be a parent of the + # current scope. + + parameterIndex @20 :UInt16; + # Index of the parameter within the generic type's parameter list. + } + + implicitMethodParameter :group { + # This is actually a reference to an implicit (generic) parameter of a method. The only + # legal context for this type to appear is inside Method.paramBrand or Method.resultBrand. + + parameterIndex @24 :UInt16; + } + } + } +} + +struct Brand { + # Specifies bindings for parameters of generics. Since these bindings turn a generic into a + # non-generic, we call it the "brand". + + scopes @0 :List(Scope); + # For each of the target type and each of its parent scopes, a parameterization may be included + # in this list. If no parameterization is included for a particular relevant scope, then either + # that scope has no parameters or all parameters should be considered to be `AnyPointer`. + + struct Scope { + scopeId @0 :Id; + # ID of the scope to which these params apply. + + union { + bind @1 :List(Binding); + # List of parameter bindings. + + inherit @2 :Void; + # The place where this Brand appears is actually within this scope or a sub-scope, + # and the bindings for this scope should be inherited from the reference point. + } + } + + struct Binding { + union { + unbound @0 :Void; + type @1 :Type; + + # TODO(someday): Allow non-type parameters? Unsure if useful. + } + } +} + +struct Value { + # Represents a value, e.g. a field default value, constant value, or annotation value. + + union { + # The ordinals intentionally match those of Type. + + void @0 :Void; + bool @1 :Bool; + int8 @2 :Int8; + int16 @3 :Int16; + int32 @4 :Int32; + int64 @5 :Int64; + uint8 @6 :UInt8; + uint16 @7 :UInt16; + uint32 @8 :UInt32; + uint64 @9 :UInt64; + float32 @10 :Float32; + float64 @11 :Float64; + text @12 :Text; + data @13 :Data; + + list @14 :AnyPointer; + + enum @15 :UInt16; + struct @16 :AnyPointer; + + interface @17 :Void; + # The only interface value that can be represented statically is "null", whose methods always + # throw exceptions. + + anyPointer @18 :AnyPointer; + } +} + +struct Annotation { + # Describes an annotation applied to a declaration. Note AnnotationNode describes the + # annotation's declaration, while this describes a use of the annotation. + + id @0 :Id; + # ID of the annotation node. + + brand @2 :Brand; + # Brand of the annotation. + # + # Note that the annotation itself is not allowed to be parameterized, but its scope might be. + + value @1 :Value; +} + +enum ElementSize { + # Possible element sizes for encoded lists. These correspond exactly to the possible values of + # the 3-bit element size component of a list pointer. + + empty @0; # aka "void", but that's a keyword. + bit @1; + byte @2; + twoBytes @3; + fourBytes @4; + eightBytes @5; + pointer @6; + inlineComposite @7; +} + +struct CapnpVersion { + major @0 :UInt16; + minor @1 :UInt8; + micro @2 :UInt8; +} + +struct CodeGeneratorRequest { + capnpVersion @2 :CapnpVersion; + # Version of the `capnp` executable. Generally, code generators should ignore this, but the code + # generators that ship with `capnp` itself will print a warning if this mismatches since that + # probably indicates something is misconfigured. + # + # The first version of 'capnp' to set this was 0.6.0. So, if it's missing, the compiler version + # is older than that. + + nodes @0 :List(Node); + # All nodes parsed by the compiler, including for the files on the command line and their + # imports. + + requestedFiles @1 :List(RequestedFile); + # Files which were listed on the command line. + + struct RequestedFile { + id @0 :Id; + # ID of the file. + + filename @1 :Text; + # Name of the file as it appeared on the command-line (minus the src-prefix). You may use + # this to decide where to write the output. + + imports @2 :List(Import); + # List of all imported paths seen in this file. + + struct Import { + id @0 :Id; + # ID of the imported file. + + name @1 :Text; + # Name which *this* file used to refer to the foreign file. This may be a relative name. + # This information is provided because it might be useful for code generation, e.g. to + # generate #include directives in C++. We don't put this in Node.file because this + # information is only meaningful at compile time anyway. + # + # (On Zooko's triangle, this is the import's petname according to the importing file.) + } + } +} diff --git a/phonelibs/capnp-cpp/include/capnp/schema.capnp.h b/phonelibs/capnp-cpp/include/capnp/schema.capnp.h new file mode 100644 index 00000000000000..1f116c9f8fe7af --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema.capnp.h @@ -0,0 +1,7861 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: schema.capnp + +#ifndef CAPNP_INCLUDED_a93fc509624c72d9_ +#define CAPNP_INCLUDED_a93fc509624c72d9_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(e682ab4cf923a417); +CAPNP_DECLARE_SCHEMA(b9521bccf10fa3b1); +CAPNP_DECLARE_SCHEMA(debf55bbfa0fc242); +CAPNP_DECLARE_SCHEMA(9ea0b19b37fb4435); +CAPNP_DECLARE_SCHEMA(b54ab3364333f598); +CAPNP_DECLARE_SCHEMA(e82753cff0c2218f); +CAPNP_DECLARE_SCHEMA(b18aa5ac7a0d9420); +CAPNP_DECLARE_SCHEMA(ec1619d4400a0290); +CAPNP_DECLARE_SCHEMA(9aad50a41f4af45f); +CAPNP_DECLARE_SCHEMA(97b14cbe7cfec712); +CAPNP_DECLARE_SCHEMA(c42305476bb4746f); +CAPNP_DECLARE_SCHEMA(cafccddb68db1d11); +CAPNP_DECLARE_SCHEMA(bb90d5c287870be6); +CAPNP_DECLARE_SCHEMA(978a7cebdc549a4d); +CAPNP_DECLARE_SCHEMA(a9962a9ed0a4d7f8); +CAPNP_DECLARE_SCHEMA(9500cce23b334d80); +CAPNP_DECLARE_SCHEMA(d07378ede1f9cc60); +CAPNP_DECLARE_SCHEMA(87e739250a60ea97); +CAPNP_DECLARE_SCHEMA(9e0e78711a7f87a9); +CAPNP_DECLARE_SCHEMA(ac3a6f60ef4cc6d3); +CAPNP_DECLARE_SCHEMA(ed8bca69f7fb0cbf); +CAPNP_DECLARE_SCHEMA(c2573fe8a23e49f1); +CAPNP_DECLARE_SCHEMA(8e3b5f79fe593656); +CAPNP_DECLARE_SCHEMA(9dd1f724f4614a85); +CAPNP_DECLARE_SCHEMA(baefc9120c56e274); +CAPNP_DECLARE_SCHEMA(903455f06065422b); +CAPNP_DECLARE_SCHEMA(abd73485a9636bc9); +CAPNP_DECLARE_SCHEMA(c863cd16969ee7fc); +CAPNP_DECLARE_SCHEMA(ce23dcd2d7b00c9b); +CAPNP_DECLARE_SCHEMA(f1c8950dab257542); +CAPNP_DECLARE_SCHEMA(d1958f7dba521926); +enum class ElementSize_d1958f7dba521926: uint16_t { + EMPTY, + BIT, + BYTE, + TWO_BYTES, + FOUR_BYTES, + EIGHT_BYTES, + POINTER, + INLINE_COMPOSITE, +}; +CAPNP_DECLARE_ENUM(ElementSize, d1958f7dba521926); +CAPNP_DECLARE_SCHEMA(d85d305b7d839963); +CAPNP_DECLARE_SCHEMA(bfc546f6210ad7ce); +CAPNP_DECLARE_SCHEMA(cfea0eb02e810062); +CAPNP_DECLARE_SCHEMA(ae504193122357e5); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace schema { + +struct Node { + Node() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + FILE, + STRUCT, + ENUM, + INTERFACE, + CONST, + ANNOTATION, + }; + struct Parameter; + struct NestedNode; + struct Struct; + struct Enum; + struct Interface; + struct Const; + struct Annotation; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e682ab4cf923a417, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Parameter { + Parameter() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b9521bccf10fa3b1, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::NestedNode { + NestedNode() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(debf55bbfa0fc242, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Struct { + Struct() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9ea0b19b37fb4435, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Enum { + Enum() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b54ab3364333f598, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Interface { + Interface() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e82753cff0c2218f, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Const { + Const() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b18aa5ac7a0d9420, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Annotation { + Annotation() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ec1619d4400a0290, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field { + Field() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + SLOT, + GROUP, + }; + static constexpr ::uint16_t NO_DISCRIMINANT = 65535u; + struct Slot; + struct Group; + struct Ordinal; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9aad50a41f4af45f, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field::Slot { + Slot() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c42305476bb4746f, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field::Group { + Group() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cafccddb68db1d11, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field::Ordinal { + Ordinal() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + IMPLICIT, + EXPLICIT, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bb90d5c287870be6, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Enumerant { + Enumerant() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(978a7cebdc549a4d, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Superclass { + Superclass() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a9962a9ed0a4d7f8, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Method { + Method() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9500cce23b334d80, 3, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type { + Type() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + VOID, + BOOL, + INT8, + INT16, + INT32, + INT64, + UINT8, + UINT16, + UINT32, + UINT64, + FLOAT32, + FLOAT64, + TEXT, + DATA, + LIST, + ENUM, + STRUCT, + INTERFACE, + ANY_POINTER, + }; + struct List; + struct Enum; + struct Struct; + struct Interface; + struct AnyPointer; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d07378ede1f9cc60, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::List { + List() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(87e739250a60ea97, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::Enum { + Enum() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9e0e78711a7f87a9, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::Struct { + Struct() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ac3a6f60ef4cc6d3, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::Interface { + Interface() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ed8bca69f7fb0cbf, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer { + AnyPointer() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + UNCONSTRAINED, + PARAMETER, + IMPLICIT_METHOD_PARAMETER, + }; + struct Unconstrained; + struct Parameter; + struct ImplicitMethodParameter; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c2573fe8a23e49f1, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer::Unconstrained { + Unconstrained() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + ANY_KIND, + STRUCT, + LIST, + CAPABILITY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8e3b5f79fe593656, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer::Parameter { + Parameter() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9dd1f724f4614a85, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer::ImplicitMethodParameter { + ImplicitMethodParameter() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(baefc9120c56e274, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Brand { + Brand() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Scope; + struct Binding; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(903455f06065422b, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Brand::Scope { + Scope() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + BIND, + INHERIT, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(abd73485a9636bc9, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Brand::Binding { + Binding() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + UNBOUND, + TYPE, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c863cd16969ee7fc, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Value { + Value() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + VOID, + BOOL, + INT8, + INT16, + INT32, + INT64, + UINT8, + UINT16, + UINT32, + UINT64, + FLOAT32, + FLOAT64, + TEXT, + DATA, + LIST, + ENUM, + STRUCT, + INTERFACE, + ANY_POINTER, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ce23dcd2d7b00c9b, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Annotation { + Annotation() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f1c8950dab257542, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +typedef ::capnp::schemas::ElementSize_d1958f7dba521926 ElementSize; + +struct CapnpVersion { + CapnpVersion() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d85d305b7d839963, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CodeGeneratorRequest { + CodeGeneratorRequest() = delete; + + class Reader; + class Builder; + class Pipeline; + struct RequestedFile; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bfc546f6210ad7ce, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CodeGeneratorRequest::RequestedFile { + RequestedFile() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Import; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cfea0eb02e810062, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CodeGeneratorRequest::RequestedFile::Import { + Import() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ae504193122357e5, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class Node::Reader { +public: + typedef Node Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint64_t getId() const; + + inline bool hasDisplayName() const; + inline ::capnp::Text::Reader getDisplayName() const; + + inline ::uint32_t getDisplayNamePrefixLength() const; + + inline ::uint64_t getScopeId() const; + + inline bool hasNestedNodes() const; + inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader getNestedNodes() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + + inline bool isFile() const; + inline ::capnp::Void getFile() const; + + inline bool isStruct() const; + inline typename Struct::Reader getStruct() const; + + inline bool isEnum() const; + inline typename Enum::Reader getEnum() const; + + inline bool isInterface() const; + inline typename Interface::Reader getInterface() const; + + inline bool isConst() const; + inline typename Const::Reader getConst() const; + + inline bool isAnnotation() const; + inline typename Annotation::Reader getAnnotation() const; + + inline bool hasParameters() const; + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader getParameters() const; + + inline bool getIsGeneric() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Builder { +public: + typedef Node Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasDisplayName(); + inline ::capnp::Text::Builder getDisplayName(); + inline void setDisplayName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initDisplayName(unsigned int size); + inline void adoptDisplayName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownDisplayName(); + + inline ::uint32_t getDisplayNamePrefixLength(); + inline void setDisplayNamePrefixLength( ::uint32_t value); + + inline ::uint64_t getScopeId(); + inline void setScopeId( ::uint64_t value); + + inline bool hasNestedNodes(); + inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder getNestedNodes(); + inline void setNestedNodes( ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader value); + inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder initNestedNodes(unsigned int size); + inline void adoptNestedNodes(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>> disownNestedNodes(); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + + inline bool isFile(); + inline ::capnp::Void getFile(); + inline void setFile( ::capnp::Void value = ::capnp::VOID); + + inline bool isStruct(); + inline typename Struct::Builder getStruct(); + inline typename Struct::Builder initStruct(); + + inline bool isEnum(); + inline typename Enum::Builder getEnum(); + inline typename Enum::Builder initEnum(); + + inline bool isInterface(); + inline typename Interface::Builder getInterface(); + inline typename Interface::Builder initInterface(); + + inline bool isConst(); + inline typename Const::Builder getConst(); + inline typename Const::Builder initConst(); + + inline bool isAnnotation(); + inline typename Annotation::Builder getAnnotation(); + inline typename Annotation::Builder initAnnotation(); + + inline bool hasParameters(); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder getParameters(); + inline void setParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder initParameters(unsigned int size); + inline void adoptParameters(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> disownParameters(); + + inline bool getIsGeneric(); + inline void setIsGeneric(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Pipeline { +public: + typedef Node Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Parameter::Reader { +public: + typedef Parameter Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Parameter::Builder { +public: + typedef Parameter Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Parameter::Pipeline { +public: + typedef Parameter Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::NestedNode::Reader { +public: + typedef NestedNode Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint64_t getId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::NestedNode::Builder { +public: + typedef NestedNode Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::NestedNode::Pipeline { +public: + typedef NestedNode Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Struct::Reader { +public: + typedef Struct Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getDataWordCount() const; + + inline ::uint16_t getPointerCount() const; + + inline ::capnp::schema::ElementSize getPreferredListEncoding() const; + + inline bool getIsGroup() const; + + inline ::uint16_t getDiscriminantCount() const; + + inline ::uint32_t getDiscriminantOffset() const; + + inline bool hasFields() const; + inline ::capnp::List< ::capnp::schema::Field>::Reader getFields() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Struct::Builder { +public: + typedef Struct Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getDataWordCount(); + inline void setDataWordCount( ::uint16_t value); + + inline ::uint16_t getPointerCount(); + inline void setPointerCount( ::uint16_t value); + + inline ::capnp::schema::ElementSize getPreferredListEncoding(); + inline void setPreferredListEncoding( ::capnp::schema::ElementSize value); + + inline bool getIsGroup(); + inline void setIsGroup(bool value); + + inline ::uint16_t getDiscriminantCount(); + inline void setDiscriminantCount( ::uint16_t value); + + inline ::uint32_t getDiscriminantOffset(); + inline void setDiscriminantOffset( ::uint32_t value); + + inline bool hasFields(); + inline ::capnp::List< ::capnp::schema::Field>::Builder getFields(); + inline void setFields( ::capnp::List< ::capnp::schema::Field>::Reader value); + inline ::capnp::List< ::capnp::schema::Field>::Builder initFields(unsigned int size); + inline void adoptFields(::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>> disownFields(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Struct::Pipeline { +public: + typedef Struct Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Enum::Reader { +public: + typedef Enum Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasEnumerants() const; + inline ::capnp::List< ::capnp::schema::Enumerant>::Reader getEnumerants() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Enum::Builder { +public: + typedef Enum Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasEnumerants(); + inline ::capnp::List< ::capnp::schema::Enumerant>::Builder getEnumerants(); + inline void setEnumerants( ::capnp::List< ::capnp::schema::Enumerant>::Reader value); + inline ::capnp::List< ::capnp::schema::Enumerant>::Builder initEnumerants(unsigned int size); + inline void adoptEnumerants(::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>> disownEnumerants(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Enum::Pipeline { +public: + typedef Enum Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Interface::Reader { +public: + typedef Interface Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasMethods() const; + inline ::capnp::List< ::capnp::schema::Method>::Reader getMethods() const; + + inline bool hasSuperclasses() const; + inline ::capnp::List< ::capnp::schema::Superclass>::Reader getSuperclasses() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Interface::Builder { +public: + typedef Interface Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasMethods(); + inline ::capnp::List< ::capnp::schema::Method>::Builder getMethods(); + inline void setMethods( ::capnp::List< ::capnp::schema::Method>::Reader value); + inline ::capnp::List< ::capnp::schema::Method>::Builder initMethods(unsigned int size); + inline void adoptMethods(::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>> disownMethods(); + + inline bool hasSuperclasses(); + inline ::capnp::List< ::capnp::schema::Superclass>::Builder getSuperclasses(); + inline void setSuperclasses( ::capnp::List< ::capnp::schema::Superclass>::Reader value); + inline ::capnp::List< ::capnp::schema::Superclass>::Builder initSuperclasses(unsigned int size); + inline void adoptSuperclasses(::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>> disownSuperclasses(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Interface::Pipeline { +public: + typedef Interface Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Const::Reader { +public: + typedef Const Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + + inline bool hasValue() const; + inline ::capnp::schema::Value::Reader getValue() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Const::Builder { +public: + typedef Const Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + + inline bool hasValue(); + inline ::capnp::schema::Value::Builder getValue(); + inline void setValue( ::capnp::schema::Value::Reader value); + inline ::capnp::schema::Value::Builder initValue(); + inline void adoptValue(::capnp::Orphan< ::capnp::schema::Value>&& value); + inline ::capnp::Orphan< ::capnp::schema::Value> disownValue(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Const::Pipeline { +public: + typedef Const Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getType(); + inline ::capnp::schema::Value::Pipeline getValue(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Annotation::Reader { +public: + typedef Annotation Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + + inline bool getTargetsFile() const; + + inline bool getTargetsConst() const; + + inline bool getTargetsEnum() const; + + inline bool getTargetsEnumerant() const; + + inline bool getTargetsStruct() const; + + inline bool getTargetsField() const; + + inline bool getTargetsUnion() const; + + inline bool getTargetsGroup() const; + + inline bool getTargetsInterface() const; + + inline bool getTargetsMethod() const; + + inline bool getTargetsParam() const; + + inline bool getTargetsAnnotation() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Annotation::Builder { +public: + typedef Annotation Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + + inline bool getTargetsFile(); + inline void setTargetsFile(bool value); + + inline bool getTargetsConst(); + inline void setTargetsConst(bool value); + + inline bool getTargetsEnum(); + inline void setTargetsEnum(bool value); + + inline bool getTargetsEnumerant(); + inline void setTargetsEnumerant(bool value); + + inline bool getTargetsStruct(); + inline void setTargetsStruct(bool value); + + inline bool getTargetsField(); + inline void setTargetsField(bool value); + + inline bool getTargetsUnion(); + inline void setTargetsUnion(bool value); + + inline bool getTargetsGroup(); + inline void setTargetsGroup(bool value); + + inline bool getTargetsInterface(); + inline void setTargetsInterface(bool value); + + inline bool getTargetsMethod(); + inline void setTargetsMethod(bool value); + + inline bool getTargetsParam(); + inline void setTargetsParam(bool value); + + inline bool getTargetsAnnotation(); + inline void setTargetsAnnotation(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Annotation::Pipeline { +public: + typedef Annotation Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getType(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Reader { +public: + typedef Field Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint16_t getCodeOrder() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + + inline ::uint16_t getDiscriminantValue() const; + + inline bool isSlot() const; + inline typename Slot::Reader getSlot() const; + + inline bool isGroup() const; + inline typename Group::Reader getGroup() const; + + inline typename Ordinal::Reader getOrdinal() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Builder { +public: + typedef Field Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint16_t getCodeOrder(); + inline void setCodeOrder( ::uint16_t value); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + + inline ::uint16_t getDiscriminantValue(); + inline void setDiscriminantValue( ::uint16_t value); + + inline bool isSlot(); + inline typename Slot::Builder getSlot(); + inline typename Slot::Builder initSlot(); + + inline bool isGroup(); + inline typename Group::Builder getGroup(); + inline typename Group::Builder initGroup(); + + inline typename Ordinal::Builder getOrdinal(); + inline typename Ordinal::Builder initOrdinal(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Pipeline { +public: + typedef Field Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline typename Ordinal::Pipeline getOrdinal(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Slot::Reader { +public: + typedef Slot Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getOffset() const; + + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + + inline bool hasDefaultValue() const; + inline ::capnp::schema::Value::Reader getDefaultValue() const; + + inline bool getHadExplicitDefault() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Slot::Builder { +public: + typedef Slot Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getOffset(); + inline void setOffset( ::uint32_t value); + + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + + inline bool hasDefaultValue(); + inline ::capnp::schema::Value::Builder getDefaultValue(); + inline void setDefaultValue( ::capnp::schema::Value::Reader value); + inline ::capnp::schema::Value::Builder initDefaultValue(); + inline void adoptDefaultValue(::capnp::Orphan< ::capnp::schema::Value>&& value); + inline ::capnp::Orphan< ::capnp::schema::Value> disownDefaultValue(); + + inline bool getHadExplicitDefault(); + inline void setHadExplicitDefault(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Slot::Pipeline { +public: + typedef Slot Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getType(); + inline ::capnp::schema::Value::Pipeline getDefaultValue(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Group::Reader { +public: + typedef Group Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Group::Builder { +public: + typedef Group Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Group::Pipeline { +public: + typedef Group Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Ordinal::Reader { +public: + typedef Ordinal Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isImplicit() const; + inline ::capnp::Void getImplicit() const; + + inline bool isExplicit() const; + inline ::uint16_t getExplicit() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Ordinal::Builder { +public: + typedef Ordinal Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isImplicit(); + inline ::capnp::Void getImplicit(); + inline void setImplicit( ::capnp::Void value = ::capnp::VOID); + + inline bool isExplicit(); + inline ::uint16_t getExplicit(); + inline void setExplicit( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Ordinal::Pipeline { +public: + typedef Ordinal Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Enumerant::Reader { +public: + typedef Enumerant Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint16_t getCodeOrder() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Enumerant::Builder { +public: + typedef Enumerant Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint16_t getCodeOrder(); + inline void setCodeOrder( ::uint16_t value); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Enumerant::Pipeline { +public: + typedef Enumerant Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Superclass::Reader { +public: + typedef Superclass Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Superclass::Builder { +public: + typedef Superclass Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Superclass::Pipeline { +public: + typedef Superclass Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Method::Reader { +public: + typedef Method Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint16_t getCodeOrder() const; + + inline ::uint64_t getParamStructType() const; + + inline ::uint64_t getResultStructType() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + + inline bool hasParamBrand() const; + inline ::capnp::schema::Brand::Reader getParamBrand() const; + + inline bool hasResultBrand() const; + inline ::capnp::schema::Brand::Reader getResultBrand() const; + + inline bool hasImplicitParameters() const; + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader getImplicitParameters() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Method::Builder { +public: + typedef Method Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint16_t getCodeOrder(); + inline void setCodeOrder( ::uint16_t value); + + inline ::uint64_t getParamStructType(); + inline void setParamStructType( ::uint64_t value); + + inline ::uint64_t getResultStructType(); + inline void setResultStructType( ::uint64_t value); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + + inline bool hasParamBrand(); + inline ::capnp::schema::Brand::Builder getParamBrand(); + inline void setParamBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initParamBrand(); + inline void adoptParamBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownParamBrand(); + + inline bool hasResultBrand(); + inline ::capnp::schema::Brand::Builder getResultBrand(); + inline void setResultBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initResultBrand(); + inline void adoptResultBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownResultBrand(); + + inline bool hasImplicitParameters(); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder getImplicitParameters(); + inline void setImplicitParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder initImplicitParameters(unsigned int size); + inline void adoptImplicitParameters(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> disownImplicitParameters(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Method::Pipeline { +public: + typedef Method Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getParamBrand(); + inline ::capnp::schema::Brand::Pipeline getResultBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Reader { +public: + typedef Type Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isVoid() const; + inline ::capnp::Void getVoid() const; + + inline bool isBool() const; + inline ::capnp::Void getBool() const; + + inline bool isInt8() const; + inline ::capnp::Void getInt8() const; + + inline bool isInt16() const; + inline ::capnp::Void getInt16() const; + + inline bool isInt32() const; + inline ::capnp::Void getInt32() const; + + inline bool isInt64() const; + inline ::capnp::Void getInt64() const; + + inline bool isUint8() const; + inline ::capnp::Void getUint8() const; + + inline bool isUint16() const; + inline ::capnp::Void getUint16() const; + + inline bool isUint32() const; + inline ::capnp::Void getUint32() const; + + inline bool isUint64() const; + inline ::capnp::Void getUint64() const; + + inline bool isFloat32() const; + inline ::capnp::Void getFloat32() const; + + inline bool isFloat64() const; + inline ::capnp::Void getFloat64() const; + + inline bool isText() const; + inline ::capnp::Void getText() const; + + inline bool isData() const; + inline ::capnp::Void getData() const; + + inline bool isList() const; + inline typename List::Reader getList() const; + + inline bool isEnum() const; + inline typename Enum::Reader getEnum() const; + + inline bool isStruct() const; + inline typename Struct::Reader getStruct() const; + + inline bool isInterface() const; + inline typename Interface::Reader getInterface() const; + + inline bool isAnyPointer() const; + inline typename AnyPointer::Reader getAnyPointer() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Builder { +public: + typedef Type Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isVoid(); + inline ::capnp::Void getVoid(); + inline void setVoid( ::capnp::Void value = ::capnp::VOID); + + inline bool isBool(); + inline ::capnp::Void getBool(); + inline void setBool( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt8(); + inline ::capnp::Void getInt8(); + inline void setInt8( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt16(); + inline ::capnp::Void getInt16(); + inline void setInt16( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt32(); + inline ::capnp::Void getInt32(); + inline void setInt32( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt64(); + inline ::capnp::Void getInt64(); + inline void setInt64( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint8(); + inline ::capnp::Void getUint8(); + inline void setUint8( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint16(); + inline ::capnp::Void getUint16(); + inline void setUint16( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint32(); + inline ::capnp::Void getUint32(); + inline void setUint32( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint64(); + inline ::capnp::Void getUint64(); + inline void setUint64( ::capnp::Void value = ::capnp::VOID); + + inline bool isFloat32(); + inline ::capnp::Void getFloat32(); + inline void setFloat32( ::capnp::Void value = ::capnp::VOID); + + inline bool isFloat64(); + inline ::capnp::Void getFloat64(); + inline void setFloat64( ::capnp::Void value = ::capnp::VOID); + + inline bool isText(); + inline ::capnp::Void getText(); + inline void setText( ::capnp::Void value = ::capnp::VOID); + + inline bool isData(); + inline ::capnp::Void getData(); + inline void setData( ::capnp::Void value = ::capnp::VOID); + + inline bool isList(); + inline typename List::Builder getList(); + inline typename List::Builder initList(); + + inline bool isEnum(); + inline typename Enum::Builder getEnum(); + inline typename Enum::Builder initEnum(); + + inline bool isStruct(); + inline typename Struct::Builder getStruct(); + inline typename Struct::Builder initStruct(); + + inline bool isInterface(); + inline typename Interface::Builder getInterface(); + inline typename Interface::Builder initInterface(); + + inline bool isAnyPointer(); + inline typename AnyPointer::Builder getAnyPointer(); + inline typename AnyPointer::Builder initAnyPointer(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Pipeline { +public: + typedef Type Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::List::Reader { +public: + typedef List Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasElementType() const; + inline ::capnp::schema::Type::Reader getElementType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::List::Builder { +public: + typedef List Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasElementType(); + inline ::capnp::schema::Type::Builder getElementType(); + inline void setElementType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initElementType(); + inline void adoptElementType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownElementType(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::List::Pipeline { +public: + typedef List Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getElementType(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Enum::Reader { +public: + typedef Enum Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Enum::Builder { +public: + typedef Enum Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Enum::Pipeline { +public: + typedef Enum Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Struct::Reader { +public: + typedef Struct Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Struct::Builder { +public: + typedef Struct Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Struct::Pipeline { +public: + typedef Struct Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Interface::Reader { +public: + typedef Interface Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Interface::Builder { +public: + typedef Interface Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Interface::Pipeline { +public: + typedef Interface Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::Reader { +public: + typedef AnyPointer Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isUnconstrained() const; + inline typename Unconstrained::Reader getUnconstrained() const; + + inline bool isParameter() const; + inline typename Parameter::Reader getParameter() const; + + inline bool isImplicitMethodParameter() const; + inline typename ImplicitMethodParameter::Reader getImplicitMethodParameter() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::Builder { +public: + typedef AnyPointer Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isUnconstrained(); + inline typename Unconstrained::Builder getUnconstrained(); + inline typename Unconstrained::Builder initUnconstrained(); + + inline bool isParameter(); + inline typename Parameter::Builder getParameter(); + inline typename Parameter::Builder initParameter(); + + inline bool isImplicitMethodParameter(); + inline typename ImplicitMethodParameter::Builder getImplicitMethodParameter(); + inline typename ImplicitMethodParameter::Builder initImplicitMethodParameter(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::Pipeline { +public: + typedef AnyPointer Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::Unconstrained::Reader { +public: + typedef Unconstrained Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isAnyKind() const; + inline ::capnp::Void getAnyKind() const; + + inline bool isStruct() const; + inline ::capnp::Void getStruct() const; + + inline bool isList() const; + inline ::capnp::Void getList() const; + + inline bool isCapability() const; + inline ::capnp::Void getCapability() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::Unconstrained::Builder { +public: + typedef Unconstrained Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isAnyKind(); + inline ::capnp::Void getAnyKind(); + inline void setAnyKind( ::capnp::Void value = ::capnp::VOID); + + inline bool isStruct(); + inline ::capnp::Void getStruct(); + inline void setStruct( ::capnp::Void value = ::capnp::VOID); + + inline bool isList(); + inline ::capnp::Void getList(); + inline void setList( ::capnp::Void value = ::capnp::VOID); + + inline bool isCapability(); + inline ::capnp::Void getCapability(); + inline void setCapability( ::capnp::Void value = ::capnp::VOID); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::Unconstrained::Pipeline { +public: + typedef Unconstrained Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::Parameter::Reader { +public: + typedef Parameter Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getScopeId() const; + + inline ::uint16_t getParameterIndex() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::Parameter::Builder { +public: + typedef Parameter Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getScopeId(); + inline void setScopeId( ::uint64_t value); + + inline ::uint16_t getParameterIndex(); + inline void setParameterIndex( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::Parameter::Pipeline { +public: + typedef Parameter Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::ImplicitMethodParameter::Reader { +public: + typedef ImplicitMethodParameter Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getParameterIndex() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::ImplicitMethodParameter::Builder { +public: + typedef ImplicitMethodParameter Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getParameterIndex(); + inline void setParameterIndex( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::ImplicitMethodParameter::Pipeline { +public: + typedef ImplicitMethodParameter Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Brand::Reader { +public: + typedef Brand Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasScopes() const; + inline ::capnp::List< ::capnp::schema::Brand::Scope>::Reader getScopes() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Brand::Builder { +public: + typedef Brand Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasScopes(); + inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder getScopes(); + inline void setScopes( ::capnp::List< ::capnp::schema::Brand::Scope>::Reader value); + inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder initScopes(unsigned int size); + inline void adoptScopes(::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>> disownScopes(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Brand::Pipeline { +public: + typedef Brand Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Brand::Scope::Reader { +public: + typedef Scope Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint64_t getScopeId() const; + + inline bool isBind() const; + inline bool hasBind() const; + inline ::capnp::List< ::capnp::schema::Brand::Binding>::Reader getBind() const; + + inline bool isInherit() const; + inline ::capnp::Void getInherit() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Brand::Scope::Builder { +public: + typedef Scope Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint64_t getScopeId(); + inline void setScopeId( ::uint64_t value); + + inline bool isBind(); + inline bool hasBind(); + inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder getBind(); + inline void setBind( ::capnp::List< ::capnp::schema::Brand::Binding>::Reader value); + inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder initBind(unsigned int size); + inline void adoptBind(::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>> disownBind(); + + inline bool isInherit(); + inline ::capnp::Void getInherit(); + inline void setInherit( ::capnp::Void value = ::capnp::VOID); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Brand::Scope::Pipeline { +public: + typedef Scope Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Brand::Binding::Reader { +public: + typedef Binding Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isUnbound() const; + inline ::capnp::Void getUnbound() const; + + inline bool isType() const; + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Brand::Binding::Builder { +public: + typedef Binding Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isUnbound(); + inline ::capnp::Void getUnbound(); + inline void setUnbound( ::capnp::Void value = ::capnp::VOID); + + inline bool isType(); + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Brand::Binding::Pipeline { +public: + typedef Binding Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Value::Reader { +public: + typedef Value Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isVoid() const; + inline ::capnp::Void getVoid() const; + + inline bool isBool() const; + inline bool getBool() const; + + inline bool isInt8() const; + inline ::int8_t getInt8() const; + + inline bool isInt16() const; + inline ::int16_t getInt16() const; + + inline bool isInt32() const; + inline ::int32_t getInt32() const; + + inline bool isInt64() const; + inline ::int64_t getInt64() const; + + inline bool isUint8() const; + inline ::uint8_t getUint8() const; + + inline bool isUint16() const; + inline ::uint16_t getUint16() const; + + inline bool isUint32() const; + inline ::uint32_t getUint32() const; + + inline bool isUint64() const; + inline ::uint64_t getUint64() const; + + inline bool isFloat32() const; + inline float getFloat32() const; + + inline bool isFloat64() const; + inline double getFloat64() const; + + inline bool isText() const; + inline bool hasText() const; + inline ::capnp::Text::Reader getText() const; + + inline bool isData() const; + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + + inline bool isList() const; + inline bool hasList() const; + inline ::capnp::AnyPointer::Reader getList() const; + + inline bool isEnum() const; + inline ::uint16_t getEnum() const; + + inline bool isStruct() const; + inline bool hasStruct() const; + inline ::capnp::AnyPointer::Reader getStruct() const; + + inline bool isInterface() const; + inline ::capnp::Void getInterface() const; + + inline bool isAnyPointer() const; + inline bool hasAnyPointer() const; + inline ::capnp::AnyPointer::Reader getAnyPointer() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Value::Builder { +public: + typedef Value Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isVoid(); + inline ::capnp::Void getVoid(); + inline void setVoid( ::capnp::Void value = ::capnp::VOID); + + inline bool isBool(); + inline bool getBool(); + inline void setBool(bool value); + + inline bool isInt8(); + inline ::int8_t getInt8(); + inline void setInt8( ::int8_t value); + + inline bool isInt16(); + inline ::int16_t getInt16(); + inline void setInt16( ::int16_t value); + + inline bool isInt32(); + inline ::int32_t getInt32(); + inline void setInt32( ::int32_t value); + + inline bool isInt64(); + inline ::int64_t getInt64(); + inline void setInt64( ::int64_t value); + + inline bool isUint8(); + inline ::uint8_t getUint8(); + inline void setUint8( ::uint8_t value); + + inline bool isUint16(); + inline ::uint16_t getUint16(); + inline void setUint16( ::uint16_t value); + + inline bool isUint32(); + inline ::uint32_t getUint32(); + inline void setUint32( ::uint32_t value); + + inline bool isUint64(); + inline ::uint64_t getUint64(); + inline void setUint64( ::uint64_t value); + + inline bool isFloat32(); + inline float getFloat32(); + inline void setFloat32(float value); + + inline bool isFloat64(); + inline double getFloat64(); + inline void setFloat64(double value); + + inline bool isText(); + inline bool hasText(); + inline ::capnp::Text::Builder getText(); + inline void setText( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initText(unsigned int size); + inline void adoptText(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownText(); + + inline bool isData(); + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + + inline bool isList(); + inline bool hasList(); + inline ::capnp::AnyPointer::Builder getList(); + inline ::capnp::AnyPointer::Builder initList(); + + inline bool isEnum(); + inline ::uint16_t getEnum(); + inline void setEnum( ::uint16_t value); + + inline bool isStruct(); + inline bool hasStruct(); + inline ::capnp::AnyPointer::Builder getStruct(); + inline ::capnp::AnyPointer::Builder initStruct(); + + inline bool isInterface(); + inline ::capnp::Void getInterface(); + inline void setInterface( ::capnp::Void value = ::capnp::VOID); + + inline bool isAnyPointer(); + inline bool hasAnyPointer(); + inline ::capnp::AnyPointer::Builder getAnyPointer(); + inline ::capnp::AnyPointer::Builder initAnyPointer(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Value::Pipeline { +public: + typedef Value Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Annotation::Reader { +public: + typedef Annotation Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasValue() const; + inline ::capnp::schema::Value::Reader getValue() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Annotation::Builder { +public: + typedef Annotation Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasValue(); + inline ::capnp::schema::Value::Builder getValue(); + inline void setValue( ::capnp::schema::Value::Reader value); + inline ::capnp::schema::Value::Builder initValue(); + inline void adoptValue(::capnp::Orphan< ::capnp::schema::Value>&& value); + inline ::capnp::Orphan< ::capnp::schema::Value> disownValue(); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Annotation::Pipeline { +public: + typedef Annotation Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Value::Pipeline getValue(); + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CapnpVersion::Reader { +public: + typedef CapnpVersion Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getMajor() const; + + inline ::uint8_t getMinor() const; + + inline ::uint8_t getMicro() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CapnpVersion::Builder { +public: + typedef CapnpVersion Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getMajor(); + inline void setMajor( ::uint16_t value); + + inline ::uint8_t getMinor(); + inline void setMinor( ::uint8_t value); + + inline ::uint8_t getMicro(); + inline void setMicro( ::uint8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CapnpVersion::Pipeline { +public: + typedef CapnpVersion Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CodeGeneratorRequest::Reader { +public: + typedef CodeGeneratorRequest Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasNodes() const; + inline ::capnp::List< ::capnp::schema::Node>::Reader getNodes() const; + + inline bool hasRequestedFiles() const; + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader getRequestedFiles() const; + + inline bool hasCapnpVersion() const; + inline ::capnp::schema::CapnpVersion::Reader getCapnpVersion() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CodeGeneratorRequest::Builder { +public: + typedef CodeGeneratorRequest Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasNodes(); + inline ::capnp::List< ::capnp::schema::Node>::Builder getNodes(); + inline void setNodes( ::capnp::List< ::capnp::schema::Node>::Reader value); + inline ::capnp::List< ::capnp::schema::Node>::Builder initNodes(unsigned int size); + inline void adoptNodes(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>> disownNodes(); + + inline bool hasRequestedFiles(); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder getRequestedFiles(); + inline void setRequestedFiles( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader value); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder initRequestedFiles(unsigned int size); + inline void adoptRequestedFiles(::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>> disownRequestedFiles(); + + inline bool hasCapnpVersion(); + inline ::capnp::schema::CapnpVersion::Builder getCapnpVersion(); + inline void setCapnpVersion( ::capnp::schema::CapnpVersion::Reader value); + inline ::capnp::schema::CapnpVersion::Builder initCapnpVersion(); + inline void adoptCapnpVersion(::capnp::Orphan< ::capnp::schema::CapnpVersion>&& value); + inline ::capnp::Orphan< ::capnp::schema::CapnpVersion> disownCapnpVersion(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CodeGeneratorRequest::Pipeline { +public: + typedef CodeGeneratorRequest Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::CapnpVersion::Pipeline getCapnpVersion(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CodeGeneratorRequest::RequestedFile::Reader { +public: + typedef RequestedFile Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasFilename() const; + inline ::capnp::Text::Reader getFilename() const; + + inline bool hasImports() const; + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader getImports() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CodeGeneratorRequest::RequestedFile::Builder { +public: + typedef RequestedFile Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasFilename(); + inline ::capnp::Text::Builder getFilename(); + inline void setFilename( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initFilename(unsigned int size); + inline void adoptFilename(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownFilename(); + + inline bool hasImports(); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder getImports(); + inline void setImports( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader value); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder initImports(unsigned int size); + inline void adoptImports(::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>> disownImports(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CodeGeneratorRequest::RequestedFile::Pipeline { +public: + typedef RequestedFile Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CodeGeneratorRequest::RequestedFile::Import::Reader { +public: + typedef Import Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CodeGeneratorRequest::RequestedFile::Import::Builder { +public: + typedef Import Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CodeGeneratorRequest::RequestedFile::Import::Pipeline { +public: + typedef Import Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::schema::Node::Which Node::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Node::Which Node::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Reader::hasDisplayName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasDisplayName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Node::Reader::getDisplayName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Node::Builder::getDisplayName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setDisplayName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Node::Builder::initDisplayName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptDisplayName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Node::Builder::disownDisplayName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Node::Reader::getDisplayNamePrefixLength() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Node::Builder::getDisplayNamePrefixLength() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setDisplayNamePrefixLength( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Node::Reader::getScopeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::Builder::getScopeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setScopeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Reader::hasNestedNodes() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasNestedNodes() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader Node::Reader::getNestedNodes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder Node::Builder::getNestedNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setNestedNodes( ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder Node::Builder::initNestedNodes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptNestedNodes( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>> Node::Builder::disownNestedNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Node::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Node::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Node::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Node::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Node::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Node::Reader::isFile() const { + return which() == Node::FILE; +} +inline bool Node::Builder::isFile() { + return which() == Node::FILE; +} +inline ::capnp::Void Node::Reader::getFile() const { + KJ_IREQUIRE((which() == Node::FILE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Node::Builder::getFile() { + KJ_IREQUIRE((which() == Node::FILE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setFile( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::FILE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Reader::isStruct() const { + return which() == Node::STRUCT; +} +inline bool Node::Builder::isStruct() { + return which() == Node::STRUCT; +} +inline typename Node::Struct::Reader Node::Reader::getStruct() const { + KJ_IREQUIRE((which() == Node::STRUCT), + "Must check which() before get()ing a union member."); + return typename Node::Struct::Reader(_reader); +} +inline typename Node::Struct::Builder Node::Builder::getStruct() { + KJ_IREQUIRE((which() == Node::STRUCT), + "Must check which() before get()ing a union member."); + return typename Node::Struct::Builder(_builder); +} +inline typename Node::Struct::Builder Node::Builder::initStruct() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::STRUCT); + _builder.setDataField< ::uint16_t>(::capnp::bounded<7>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<12>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<13>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<224>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<15>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint32_t>(::capnp::bounded<8>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Node::Struct::Builder(_builder); +} +inline bool Node::Reader::isEnum() const { + return which() == Node::ENUM; +} +inline bool Node::Builder::isEnum() { + return which() == Node::ENUM; +} +inline typename Node::Enum::Reader Node::Reader::getEnum() const { + KJ_IREQUIRE((which() == Node::ENUM), + "Must check which() before get()ing a union member."); + return typename Node::Enum::Reader(_reader); +} +inline typename Node::Enum::Builder Node::Builder::getEnum() { + KJ_IREQUIRE((which() == Node::ENUM), + "Must check which() before get()ing a union member."); + return typename Node::Enum::Builder(_builder); +} +inline typename Node::Enum::Builder Node::Builder::initEnum() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::ENUM); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Node::Enum::Builder(_builder); +} +inline bool Node::Reader::isInterface() const { + return which() == Node::INTERFACE; +} +inline bool Node::Builder::isInterface() { + return which() == Node::INTERFACE; +} +inline typename Node::Interface::Reader Node::Reader::getInterface() const { + KJ_IREQUIRE((which() == Node::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Node::Interface::Reader(_reader); +} +inline typename Node::Interface::Builder Node::Builder::getInterface() { + KJ_IREQUIRE((which() == Node::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Node::Interface::Builder(_builder); +} +inline typename Node::Interface::Builder Node::Builder::initInterface() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::INTERFACE); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + _builder.getPointerField(::capnp::bounded<4>() * ::capnp::POINTERS).clear(); + return typename Node::Interface::Builder(_builder); +} +inline bool Node::Reader::isConst() const { + return which() == Node::CONST; +} +inline bool Node::Builder::isConst() { + return which() == Node::CONST; +} +inline typename Node::Const::Reader Node::Reader::getConst() const { + KJ_IREQUIRE((which() == Node::CONST), + "Must check which() before get()ing a union member."); + return typename Node::Const::Reader(_reader); +} +inline typename Node::Const::Builder Node::Builder::getConst() { + KJ_IREQUIRE((which() == Node::CONST), + "Must check which() before get()ing a union member."); + return typename Node::Const::Builder(_builder); +} +inline typename Node::Const::Builder Node::Builder::initConst() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::CONST); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + _builder.getPointerField(::capnp::bounded<4>() * ::capnp::POINTERS).clear(); + return typename Node::Const::Builder(_builder); +} +inline bool Node::Reader::isAnnotation() const { + return which() == Node::ANNOTATION; +} +inline bool Node::Builder::isAnnotation() { + return which() == Node::ANNOTATION; +} +inline typename Node::Annotation::Reader Node::Reader::getAnnotation() const { + KJ_IREQUIRE((which() == Node::ANNOTATION), + "Must check which() before get()ing a union member."); + return typename Node::Annotation::Reader(_reader); +} +inline typename Node::Annotation::Builder Node::Builder::getAnnotation() { + KJ_IREQUIRE((which() == Node::ANNOTATION), + "Must check which() before get()ing a union member."); + return typename Node::Annotation::Builder(_builder); +} +inline typename Node::Annotation::Builder Node::Builder::initAnnotation() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::ANNOTATION); + _builder.setDataField(::capnp::bounded<112>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<113>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<114>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<115>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<116>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<117>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<118>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<119>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<120>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<121>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<122>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<123>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Node::Annotation::Builder(_builder); +} +inline bool Node::Reader::hasParameters() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasParameters() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader Node::Reader::getParameters() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Node::Builder::getParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Node::Builder::initParameters(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptParameters( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> Node::Builder::disownParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline bool Node::Reader::getIsGeneric() const { + return _reader.getDataField( + ::capnp::bounded<288>() * ::capnp::ELEMENTS); +} + +inline bool Node::Builder::getIsGeneric() { + return _builder.getDataField( + ::capnp::bounded<288>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setIsGeneric(bool value) { + _builder.setDataField( + ::capnp::bounded<288>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Parameter::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Parameter::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Node::Parameter::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Node::Parameter::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Node::Parameter::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Node::Parameter::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Node::Parameter::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Node::Parameter::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Node::NestedNode::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::NestedNode::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Node::NestedNode::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Node::NestedNode::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Node::NestedNode::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Node::NestedNode::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Node::NestedNode::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Node::NestedNode::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Node::NestedNode::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::NestedNode::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Node::NestedNode::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Node::Struct::Reader::getDataWordCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<7>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Node::Struct::Builder::getDataWordCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<7>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setDataWordCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<7>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Node::Struct::Reader::getPointerCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<12>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Node::Struct::Builder::getPointerCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<12>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setPointerCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<12>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::ElementSize Node::Struct::Reader::getPreferredListEncoding() const { + return _reader.getDataField< ::capnp::schema::ElementSize>( + ::capnp::bounded<13>() * ::capnp::ELEMENTS); +} + +inline ::capnp::schema::ElementSize Node::Struct::Builder::getPreferredListEncoding() { + return _builder.getDataField< ::capnp::schema::ElementSize>( + ::capnp::bounded<13>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setPreferredListEncoding( ::capnp::schema::ElementSize value) { + _builder.setDataField< ::capnp::schema::ElementSize>( + ::capnp::bounded<13>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Struct::Reader::getIsGroup() const { + return _reader.getDataField( + ::capnp::bounded<224>() * ::capnp::ELEMENTS); +} + +inline bool Node::Struct::Builder::getIsGroup() { + return _builder.getDataField( + ::capnp::bounded<224>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setIsGroup(bool value) { + _builder.setDataField( + ::capnp::bounded<224>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Node::Struct::Reader::getDiscriminantCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<15>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Node::Struct::Builder::getDiscriminantCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<15>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setDiscriminantCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<15>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Node::Struct::Reader::getDiscriminantOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Node::Struct::Builder::getDiscriminantOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setDiscriminantOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Struct::Reader::hasFields() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Struct::Builder::hasFields() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Field>::Reader Node::Struct::Reader::getFields() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Field>::Builder Node::Struct::Builder::getFields() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Struct::Builder::setFields( ::capnp::List< ::capnp::schema::Field>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Field>::Builder Node::Struct::Builder::initFields(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void Node::Struct::Builder::adoptFields( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>> Node::Struct::Builder::disownFields() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Enum::Reader::hasEnumerants() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Enum::Builder::hasEnumerants() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Enumerant>::Reader Node::Enum::Reader::getEnumerants() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Enumerant>::Builder Node::Enum::Builder::getEnumerants() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Enum::Builder::setEnumerants( ::capnp::List< ::capnp::schema::Enumerant>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Enumerant>::Builder Node::Enum::Builder::initEnumerants(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void Node::Enum::Builder::adoptEnumerants( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>> Node::Enum::Builder::disownEnumerants() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Interface::Reader::hasMethods() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Interface::Builder::hasMethods() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Method>::Reader Node::Interface::Reader::getMethods() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Method>::Builder Node::Interface::Builder::getMethods() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Interface::Builder::setMethods( ::capnp::List< ::capnp::schema::Method>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Method>::Builder Node::Interface::Builder::initMethods(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void Node::Interface::Builder::adoptMethods( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>> Node::Interface::Builder::disownMethods() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Interface::Reader::hasSuperclasses() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Interface::Builder::hasSuperclasses() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Superclass>::Reader Node::Interface::Reader::getSuperclasses() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Superclass>::Builder Node::Interface::Builder::getSuperclasses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Node::Interface::Builder::setSuperclasses( ::capnp::List< ::capnp::schema::Superclass>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Superclass>::Builder Node::Interface::Builder::initSuperclasses(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void Node::Interface::Builder::adoptSuperclasses( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>> Node::Interface::Builder::disownSuperclasses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool Node::Const::Reader::hasType() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Const::Builder::hasType() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Node::Const::Reader::getType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Node::Const::Builder::getType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Node::Const::Pipeline::getType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Node::Const::Builder::setType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Node::Const::Builder::initType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Const::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Node::Const::Builder::disownType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Const::Reader::hasValue() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Const::Builder::hasValue() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Value::Reader Node::Const::Reader::getValue() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Value::Builder Node::Const::Builder::getValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Value::Pipeline Node::Const::Pipeline::getValue() { + return ::capnp::schema::Value::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void Node::Const::Builder::setValue( ::capnp::schema::Value::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Value::Builder Node::Const::Builder::initValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Node::Const::Builder::adoptValue( + ::capnp::Orphan< ::capnp::schema::Value>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Value> Node::Const::Builder::disownValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool Node::Annotation::Reader::hasType() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Annotation::Builder::hasType() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Node::Annotation::Reader::getType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Node::Annotation::Builder::getType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Node::Annotation::Pipeline::getType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Node::Annotation::Builder::setType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Node::Annotation::Builder::initType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Annotation::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Node::Annotation::Builder::disownType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Annotation::Reader::getTargetsFile() const { + return _reader.getDataField( + ::capnp::bounded<112>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsFile() { + return _builder.getDataField( + ::capnp::bounded<112>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsFile(bool value) { + _builder.setDataField( + ::capnp::bounded<112>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsConst() const { + return _reader.getDataField( + ::capnp::bounded<113>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsConst() { + return _builder.getDataField( + ::capnp::bounded<113>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsConst(bool value) { + _builder.setDataField( + ::capnp::bounded<113>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsEnum() const { + return _reader.getDataField( + ::capnp::bounded<114>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsEnum() { + return _builder.getDataField( + ::capnp::bounded<114>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsEnum(bool value) { + _builder.setDataField( + ::capnp::bounded<114>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsEnumerant() const { + return _reader.getDataField( + ::capnp::bounded<115>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsEnumerant() { + return _builder.getDataField( + ::capnp::bounded<115>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsEnumerant(bool value) { + _builder.setDataField( + ::capnp::bounded<115>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsStruct() const { + return _reader.getDataField( + ::capnp::bounded<116>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsStruct() { + return _builder.getDataField( + ::capnp::bounded<116>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsStruct(bool value) { + _builder.setDataField( + ::capnp::bounded<116>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsField() const { + return _reader.getDataField( + ::capnp::bounded<117>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsField() { + return _builder.getDataField( + ::capnp::bounded<117>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsField(bool value) { + _builder.setDataField( + ::capnp::bounded<117>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsUnion() const { + return _reader.getDataField( + ::capnp::bounded<118>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsUnion() { + return _builder.getDataField( + ::capnp::bounded<118>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsUnion(bool value) { + _builder.setDataField( + ::capnp::bounded<118>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsGroup() const { + return _reader.getDataField( + ::capnp::bounded<119>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsGroup() { + return _builder.getDataField( + ::capnp::bounded<119>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsGroup(bool value) { + _builder.setDataField( + ::capnp::bounded<119>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsInterface() const { + return _reader.getDataField( + ::capnp::bounded<120>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsInterface() { + return _builder.getDataField( + ::capnp::bounded<120>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsInterface(bool value) { + _builder.setDataField( + ::capnp::bounded<120>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsMethod() const { + return _reader.getDataField( + ::capnp::bounded<121>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsMethod() { + return _builder.getDataField( + ::capnp::bounded<121>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsMethod(bool value) { + _builder.setDataField( + ::capnp::bounded<121>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsParam() const { + return _reader.getDataField( + ::capnp::bounded<122>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsParam() { + return _builder.getDataField( + ::capnp::bounded<122>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsParam(bool value) { + _builder.setDataField( + ::capnp::bounded<122>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsAnnotation() const { + return _reader.getDataField( + ::capnp::bounded<123>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsAnnotation() { + return _builder.getDataField( + ::capnp::bounded<123>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsAnnotation(bool value) { + _builder.setDataField( + ::capnp::bounded<123>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::Field::Which Field::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Field::Which Field::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline bool Field::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Field::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Field::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Field::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Field::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Field::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Field::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Field::Reader::getCodeOrder() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Field::Builder::getCodeOrder() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Field::Builder::setCodeOrder( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Field::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Field::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Field::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Field::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Field::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Field::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Field::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Field::Reader::getDiscriminantValue() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, 65535u); +} + +inline ::uint16_t Field::Builder::getDiscriminantValue() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, 65535u); +} +inline void Field::Builder::setDiscriminantValue( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value, 65535u); +} + +inline bool Field::Reader::isSlot() const { + return which() == Field::SLOT; +} +inline bool Field::Builder::isSlot() { + return which() == Field::SLOT; +} +inline typename Field::Slot::Reader Field::Reader::getSlot() const { + KJ_IREQUIRE((which() == Field::SLOT), + "Must check which() before get()ing a union member."); + return typename Field::Slot::Reader(_reader); +} +inline typename Field::Slot::Builder Field::Builder::getSlot() { + KJ_IREQUIRE((which() == Field::SLOT), + "Must check which() before get()ing a union member."); + return typename Field::Slot::Builder(_builder); +} +inline typename Field::Slot::Builder Field::Builder::initSlot() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Field::SLOT); + _builder.setDataField< ::uint32_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<128>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<2>() * ::capnp::POINTERS).clear(); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Field::Slot::Builder(_builder); +} +inline bool Field::Reader::isGroup() const { + return which() == Field::GROUP; +} +inline bool Field::Builder::isGroup() { + return which() == Field::GROUP; +} +inline typename Field::Group::Reader Field::Reader::getGroup() const { + KJ_IREQUIRE((which() == Field::GROUP), + "Must check which() before get()ing a union member."); + return typename Field::Group::Reader(_reader); +} +inline typename Field::Group::Builder Field::Builder::getGroup() { + KJ_IREQUIRE((which() == Field::GROUP), + "Must check which() before get()ing a union member."); + return typename Field::Group::Builder(_builder); +} +inline typename Field::Group::Builder Field::Builder::initGroup() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Field::GROUP); + _builder.setDataField< ::uint64_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Field::Group::Builder(_builder); +} +inline typename Field::Ordinal::Reader Field::Reader::getOrdinal() const { + return typename Field::Ordinal::Reader(_reader); +} +inline typename Field::Ordinal::Builder Field::Builder::getOrdinal() { + return typename Field::Ordinal::Builder(_builder); +} +#if !CAPNP_LITE +inline typename Field::Ordinal::Pipeline Field::Pipeline::getOrdinal() { + return typename Field::Ordinal::Pipeline(_typeless.noop()); +} +#endif // !CAPNP_LITE +inline typename Field::Ordinal::Builder Field::Builder::initOrdinal() { + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<6>() * ::capnp::ELEMENTS, 0); + return typename Field::Ordinal::Builder(_builder); +} +inline ::uint32_t Field::Slot::Reader::getOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Field::Slot::Builder::getOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Field::Slot::Builder::setOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Field::Slot::Reader::hasType() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Slot::Builder::hasType() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Field::Slot::Reader::getType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Field::Slot::Builder::getType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Field::Slot::Pipeline::getType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Field::Slot::Builder::setType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Field::Slot::Builder::initType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Field::Slot::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Field::Slot::Builder::disownType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Field::Slot::Reader::hasDefaultValue() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Slot::Builder::hasDefaultValue() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Value::Reader Field::Slot::Reader::getDefaultValue() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Value::Builder Field::Slot::Builder::getDefaultValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Value::Pipeline Field::Slot::Pipeline::getDefaultValue() { + return ::capnp::schema::Value::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Field::Slot::Builder::setDefaultValue( ::capnp::schema::Value::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Value::Builder Field::Slot::Builder::initDefaultValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Field::Slot::Builder::adoptDefaultValue( + ::capnp::Orphan< ::capnp::schema::Value>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Value> Field::Slot::Builder::disownDefaultValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Field::Slot::Reader::getHadExplicitDefault() const { + return _reader.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} + +inline bool Field::Slot::Builder::getHadExplicitDefault() { + return _builder.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} +inline void Field::Slot::Builder::setHadExplicitDefault(bool value) { + _builder.setDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Field::Group::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Field::Group::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Field::Group::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::Field::Ordinal::Which Field::Ordinal::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Field::Ordinal::Which Field::Ordinal::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline bool Field::Ordinal::Reader::isImplicit() const { + return which() == Field::Ordinal::IMPLICIT; +} +inline bool Field::Ordinal::Builder::isImplicit() { + return which() == Field::Ordinal::IMPLICIT; +} +inline ::capnp::Void Field::Ordinal::Reader::getImplicit() const { + KJ_IREQUIRE((which() == Field::Ordinal::IMPLICIT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Field::Ordinal::Builder::getImplicit() { + KJ_IREQUIRE((which() == Field::Ordinal::IMPLICIT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Field::Ordinal::Builder::setImplicit( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Field::Ordinal::IMPLICIT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Field::Ordinal::Reader::isExplicit() const { + return which() == Field::Ordinal::EXPLICIT; +} +inline bool Field::Ordinal::Builder::isExplicit() { + return which() == Field::Ordinal::EXPLICIT; +} +inline ::uint16_t Field::Ordinal::Reader::getExplicit() const { + KJ_IREQUIRE((which() == Field::Ordinal::EXPLICIT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Field::Ordinal::Builder::getExplicit() { + KJ_IREQUIRE((which() == Field::Ordinal::EXPLICIT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline void Field::Ordinal::Builder::setExplicit( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Field::Ordinal::EXPLICIT); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, value); +} + +inline bool Enumerant::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Enumerant::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Enumerant::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Enumerant::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Enumerant::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Enumerant::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Enumerant::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Enumerant::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Enumerant::Reader::getCodeOrder() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Enumerant::Builder::getCodeOrder() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Enumerant::Builder::setCodeOrder( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Enumerant::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Enumerant::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Enumerant::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Enumerant::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Enumerant::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Enumerant::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Enumerant::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Enumerant::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Superclass::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Superclass::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Superclass::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Superclass::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Superclass::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Superclass::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Superclass::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Superclass::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Superclass::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Superclass::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Superclass::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Superclass::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Method::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Method::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Method::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Method::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Method::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Method::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Method::Reader::getCodeOrder() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Method::Builder::getCodeOrder() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Method::Builder::setCodeOrder( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Method::Reader::getParamStructType() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Method::Builder::getParamStructType() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Method::Builder::setParamStructType( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Method::Reader::getResultStructType() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Method::Builder::getResultStructType() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Method::Builder::setResultStructType( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Method::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Method::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Method::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Method::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Method::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Method::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Method::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasParamBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasParamBrand() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Method::Reader::getParamBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Method::Builder::getParamBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Method::Pipeline::getParamBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Method::Builder::setParamBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Method::Builder::initParamBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Method::Builder::adoptParamBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Method::Builder::disownParamBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasResultBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasResultBrand() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Method::Reader::getResultBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Method::Builder::getResultBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Method::Pipeline::getResultBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Method::Builder::setResultBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Method::Builder::initResultBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Method::Builder::adoptResultBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Method::Builder::disownResultBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasImplicitParameters() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasImplicitParameters() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader Method::Reader::getImplicitParameters() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Method::Builder::getImplicitParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Method::Builder::setImplicitParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Method::Builder::initImplicitParameters(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void Method::Builder::adoptImplicitParameters( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> Method::Builder::disownImplicitParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Type::Which Type::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Type::Which Type::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Type::Reader::isVoid() const { + return which() == Type::VOID; +} +inline bool Type::Builder::isVoid() { + return which() == Type::VOID; +} +inline ::capnp::Void Type::Reader::getVoid() const { + KJ_IREQUIRE((which() == Type::VOID), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getVoid() { + KJ_IREQUIRE((which() == Type::VOID), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setVoid( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::VOID); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isBool() const { + return which() == Type::BOOL; +} +inline bool Type::Builder::isBool() { + return which() == Type::BOOL; +} +inline ::capnp::Void Type::Reader::getBool() const { + KJ_IREQUIRE((which() == Type::BOOL), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getBool() { + KJ_IREQUIRE((which() == Type::BOOL), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setBool( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::BOOL); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt8() const { + return which() == Type::INT8; +} +inline bool Type::Builder::isInt8() { + return which() == Type::INT8; +} +inline ::capnp::Void Type::Reader::getInt8() const { + KJ_IREQUIRE((which() == Type::INT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt8() { + KJ_IREQUIRE((which() == Type::INT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt8( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT8); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt16() const { + return which() == Type::INT16; +} +inline bool Type::Builder::isInt16() { + return which() == Type::INT16; +} +inline ::capnp::Void Type::Reader::getInt16() const { + KJ_IREQUIRE((which() == Type::INT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt16() { + KJ_IREQUIRE((which() == Type::INT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt16( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT16); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt32() const { + return which() == Type::INT32; +} +inline bool Type::Builder::isInt32() { + return which() == Type::INT32; +} +inline ::capnp::Void Type::Reader::getInt32() const { + KJ_IREQUIRE((which() == Type::INT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt32() { + KJ_IREQUIRE((which() == Type::INT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt32( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT32); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt64() const { + return which() == Type::INT64; +} +inline bool Type::Builder::isInt64() { + return which() == Type::INT64; +} +inline ::capnp::Void Type::Reader::getInt64() const { + KJ_IREQUIRE((which() == Type::INT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt64() { + KJ_IREQUIRE((which() == Type::INT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt64( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT64); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint8() const { + return which() == Type::UINT8; +} +inline bool Type::Builder::isUint8() { + return which() == Type::UINT8; +} +inline ::capnp::Void Type::Reader::getUint8() const { + KJ_IREQUIRE((which() == Type::UINT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint8() { + KJ_IREQUIRE((which() == Type::UINT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint8( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT8); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint16() const { + return which() == Type::UINT16; +} +inline bool Type::Builder::isUint16() { + return which() == Type::UINT16; +} +inline ::capnp::Void Type::Reader::getUint16() const { + KJ_IREQUIRE((which() == Type::UINT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint16() { + KJ_IREQUIRE((which() == Type::UINT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint16( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT16); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint32() const { + return which() == Type::UINT32; +} +inline bool Type::Builder::isUint32() { + return which() == Type::UINT32; +} +inline ::capnp::Void Type::Reader::getUint32() const { + KJ_IREQUIRE((which() == Type::UINT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint32() { + KJ_IREQUIRE((which() == Type::UINT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint32( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT32); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint64() const { + return which() == Type::UINT64; +} +inline bool Type::Builder::isUint64() { + return which() == Type::UINT64; +} +inline ::capnp::Void Type::Reader::getUint64() const { + KJ_IREQUIRE((which() == Type::UINT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint64() { + KJ_IREQUIRE((which() == Type::UINT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint64( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT64); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isFloat32() const { + return which() == Type::FLOAT32; +} +inline bool Type::Builder::isFloat32() { + return which() == Type::FLOAT32; +} +inline ::capnp::Void Type::Reader::getFloat32() const { + KJ_IREQUIRE((which() == Type::FLOAT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getFloat32() { + KJ_IREQUIRE((which() == Type::FLOAT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setFloat32( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::FLOAT32); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isFloat64() const { + return which() == Type::FLOAT64; +} +inline bool Type::Builder::isFloat64() { + return which() == Type::FLOAT64; +} +inline ::capnp::Void Type::Reader::getFloat64() const { + KJ_IREQUIRE((which() == Type::FLOAT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getFloat64() { + KJ_IREQUIRE((which() == Type::FLOAT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setFloat64( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::FLOAT64); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isText() const { + return which() == Type::TEXT; +} +inline bool Type::Builder::isText() { + return which() == Type::TEXT; +} +inline ::capnp::Void Type::Reader::getText() const { + KJ_IREQUIRE((which() == Type::TEXT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getText() { + KJ_IREQUIRE((which() == Type::TEXT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setText( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::TEXT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isData() const { + return which() == Type::DATA; +} +inline bool Type::Builder::isData() { + return which() == Type::DATA; +} +inline ::capnp::Void Type::Reader::getData() const { + KJ_IREQUIRE((which() == Type::DATA), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getData() { + KJ_IREQUIRE((which() == Type::DATA), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setData( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::DATA); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isList() const { + return which() == Type::LIST; +} +inline bool Type::Builder::isList() { + return which() == Type::LIST; +} +inline typename Type::List::Reader Type::Reader::getList() const { + KJ_IREQUIRE((which() == Type::LIST), + "Must check which() before get()ing a union member."); + return typename Type::List::Reader(_reader); +} +inline typename Type::List::Builder Type::Builder::getList() { + KJ_IREQUIRE((which() == Type::LIST), + "Must check which() before get()ing a union member."); + return typename Type::List::Builder(_builder); +} +inline typename Type::List::Builder Type::Builder::initList() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::LIST); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::List::Builder(_builder); +} +inline bool Type::Reader::isEnum() const { + return which() == Type::ENUM; +} +inline bool Type::Builder::isEnum() { + return which() == Type::ENUM; +} +inline typename Type::Enum::Reader Type::Reader::getEnum() const { + KJ_IREQUIRE((which() == Type::ENUM), + "Must check which() before get()ing a union member."); + return typename Type::Enum::Reader(_reader); +} +inline typename Type::Enum::Builder Type::Builder::getEnum() { + KJ_IREQUIRE((which() == Type::ENUM), + "Must check which() before get()ing a union member."); + return typename Type::Enum::Builder(_builder); +} +inline typename Type::Enum::Builder Type::Builder::initEnum() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::ENUM); + _builder.setDataField< ::uint64_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::Enum::Builder(_builder); +} +inline bool Type::Reader::isStruct() const { + return which() == Type::STRUCT; +} +inline bool Type::Builder::isStruct() { + return which() == Type::STRUCT; +} +inline typename Type::Struct::Reader Type::Reader::getStruct() const { + KJ_IREQUIRE((which() == Type::STRUCT), + "Must check which() before get()ing a union member."); + return typename Type::Struct::Reader(_reader); +} +inline typename Type::Struct::Builder Type::Builder::getStruct() { + KJ_IREQUIRE((which() == Type::STRUCT), + "Must check which() before get()ing a union member."); + return typename Type::Struct::Builder(_builder); +} +inline typename Type::Struct::Builder Type::Builder::initStruct() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::STRUCT); + _builder.setDataField< ::uint64_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::Struct::Builder(_builder); +} +inline bool Type::Reader::isInterface() const { + return which() == Type::INTERFACE; +} +inline bool Type::Builder::isInterface() { + return which() == Type::INTERFACE; +} +inline typename Type::Interface::Reader Type::Reader::getInterface() const { + KJ_IREQUIRE((which() == Type::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Type::Interface::Reader(_reader); +} +inline typename Type::Interface::Builder Type::Builder::getInterface() { + KJ_IREQUIRE((which() == Type::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Type::Interface::Builder(_builder); +} +inline typename Type::Interface::Builder Type::Builder::initInterface() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INTERFACE); + _builder.setDataField< ::uint64_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::Interface::Builder(_builder); +} +inline bool Type::Reader::isAnyPointer() const { + return which() == Type::ANY_POINTER; +} +inline bool Type::Builder::isAnyPointer() { + return which() == Type::ANY_POINTER; +} +inline typename Type::AnyPointer::Reader Type::Reader::getAnyPointer() const { + KJ_IREQUIRE((which() == Type::ANY_POINTER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Reader(_reader); +} +inline typename Type::AnyPointer::Builder Type::Builder::getAnyPointer() { + KJ_IREQUIRE((which() == Type::ANY_POINTER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Builder(_builder); +} +inline typename Type::AnyPointer::Builder Type::Builder::initAnyPointer() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::ANY_POINTER); + _builder.setDataField< ::uint16_t>(::capnp::bounded<4>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint64_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::Builder(_builder); +} +inline bool Type::List::Reader::hasElementType() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::List::Builder::hasElementType() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Type::List::Reader::getElementType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Type::List::Builder::getElementType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Type::List::Pipeline::getElementType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::List::Builder::setElementType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Type::List::Builder::initElementType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::List::Builder::adoptElementType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Type::List::Builder::disownElementType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Type::Enum::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::Enum::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Type::Enum::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Enum::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::Enum::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Type::Enum::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Type::Enum::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Type::Enum::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::Enum::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Type::Enum::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::Enum::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Type::Enum::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Type::Struct::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::Struct::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Type::Struct::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Struct::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::Struct::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Type::Struct::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Type::Struct::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Type::Struct::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::Struct::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Type::Struct::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::Struct::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Type::Struct::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Type::Interface::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::Interface::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Type::Interface::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Interface::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::Interface::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Type::Interface::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Type::Interface::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Type::Interface::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::Interface::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Type::Interface::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::Interface::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Type::Interface::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Type::AnyPointer::Which Type::AnyPointer::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Type::AnyPointer::Which Type::AnyPointer::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline bool Type::AnyPointer::Reader::isUnconstrained() const { + return which() == Type::AnyPointer::UNCONSTRAINED; +} +inline bool Type::AnyPointer::Builder::isUnconstrained() { + return which() == Type::AnyPointer::UNCONSTRAINED; +} +inline typename Type::AnyPointer::Unconstrained::Reader Type::AnyPointer::Reader::getUnconstrained() const { + KJ_IREQUIRE((which() == Type::AnyPointer::UNCONSTRAINED), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Unconstrained::Reader(_reader); +} +inline typename Type::AnyPointer::Unconstrained::Builder Type::AnyPointer::Builder::getUnconstrained() { + KJ_IREQUIRE((which() == Type::AnyPointer::UNCONSTRAINED), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Unconstrained::Builder(_builder); +} +inline typename Type::AnyPointer::Unconstrained::Builder Type::AnyPointer::Builder::initUnconstrained() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Type::AnyPointer::UNCONSTRAINED); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::Unconstrained::Builder(_builder); +} +inline bool Type::AnyPointer::Reader::isParameter() const { + return which() == Type::AnyPointer::PARAMETER; +} +inline bool Type::AnyPointer::Builder::isParameter() { + return which() == Type::AnyPointer::PARAMETER; +} +inline typename Type::AnyPointer::Parameter::Reader Type::AnyPointer::Reader::getParameter() const { + KJ_IREQUIRE((which() == Type::AnyPointer::PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Parameter::Reader(_reader); +} +inline typename Type::AnyPointer::Parameter::Builder Type::AnyPointer::Builder::getParameter() { + KJ_IREQUIRE((which() == Type::AnyPointer::PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Parameter::Builder(_builder); +} +inline typename Type::AnyPointer::Parameter::Builder Type::AnyPointer::Builder::initParameter() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Type::AnyPointer::PARAMETER); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint64_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::Parameter::Builder(_builder); +} +inline bool Type::AnyPointer::Reader::isImplicitMethodParameter() const { + return which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER; +} +inline bool Type::AnyPointer::Builder::isImplicitMethodParameter() { + return which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER; +} +inline typename Type::AnyPointer::ImplicitMethodParameter::Reader Type::AnyPointer::Reader::getImplicitMethodParameter() const { + KJ_IREQUIRE((which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::ImplicitMethodParameter::Reader(_reader); +} +inline typename Type::AnyPointer::ImplicitMethodParameter::Builder Type::AnyPointer::Builder::getImplicitMethodParameter() { + KJ_IREQUIRE((which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::ImplicitMethodParameter::Builder(_builder); +} +inline typename Type::AnyPointer::ImplicitMethodParameter::Builder Type::AnyPointer::Builder::initImplicitMethodParameter() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Type::AnyPointer::IMPLICIT_METHOD_PARAMETER); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::ImplicitMethodParameter::Builder(_builder); +} +inline ::capnp::schema::Type::AnyPointer::Unconstrained::Which Type::AnyPointer::Unconstrained::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Type::AnyPointer::Unconstrained::Which Type::AnyPointer::Unconstrained::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isAnyKind() const { + return which() == Type::AnyPointer::Unconstrained::ANY_KIND; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isAnyKind() { + return which() == Type::AnyPointer::Unconstrained::ANY_KIND; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getAnyKind() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::ANY_KIND), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getAnyKind() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::ANY_KIND), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setAnyKind( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::ANY_KIND); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isStruct() const { + return which() == Type::AnyPointer::Unconstrained::STRUCT; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isStruct() { + return which() == Type::AnyPointer::Unconstrained::STRUCT; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getStruct() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::STRUCT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getStruct() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::STRUCT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setStruct( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::STRUCT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isList() const { + return which() == Type::AnyPointer::Unconstrained::LIST; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isList() { + return which() == Type::AnyPointer::Unconstrained::LIST; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getList() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::LIST), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getList() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::LIST), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setList( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::LIST); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isCapability() const { + return which() == Type::AnyPointer::Unconstrained::CAPABILITY; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isCapability() { + return which() == Type::AnyPointer::Unconstrained::CAPABILITY; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getCapability() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::CAPABILITY), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getCapability() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::CAPABILITY), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setCapability( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::CAPABILITY); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Type::AnyPointer::Parameter::Reader::getScopeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::AnyPointer::Parameter::Builder::getScopeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Parameter::Builder::setScopeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Type::AnyPointer::Parameter::Reader::getParameterIndex() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Type::AnyPointer::Parameter::Builder::getParameterIndex() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Parameter::Builder::setParameterIndex( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Type::AnyPointer::ImplicitMethodParameter::Reader::getParameterIndex() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Type::AnyPointer::ImplicitMethodParameter::Builder::getParameterIndex() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::ImplicitMethodParameter::Builder::setParameterIndex( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline bool Brand::Reader::hasScopes() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Brand::Builder::hasScopes() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Brand::Scope>::Reader Brand::Reader::getScopes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder Brand::Builder::getScopes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Builder::setScopes( ::capnp::List< ::capnp::schema::Brand::Scope>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder Brand::Builder::initScopes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Brand::Builder::adoptScopes( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>> Brand::Builder::disownScopes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Brand::Scope::Which Brand::Scope::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Brand::Scope::Which Brand::Scope::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Brand::Scope::Reader::getScopeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Brand::Scope::Builder::getScopeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Brand::Scope::Builder::setScopeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Brand::Scope::Reader::isBind() const { + return which() == Brand::Scope::BIND; +} +inline bool Brand::Scope::Builder::isBind() { + return which() == Brand::Scope::BIND; +} +inline bool Brand::Scope::Reader::hasBind() const { + if (which() != Brand::Scope::BIND) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Brand::Scope::Builder::hasBind() { + if (which() != Brand::Scope::BIND) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Brand::Binding>::Reader Brand::Scope::Reader::getBind() const { + KJ_IREQUIRE((which() == Brand::Scope::BIND), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder Brand::Scope::Builder::getBind() { + KJ_IREQUIRE((which() == Brand::Scope::BIND), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Scope::Builder::setBind( ::capnp::List< ::capnp::schema::Brand::Binding>::Reader value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::BIND); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder Brand::Scope::Builder::initBind(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::BIND); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Brand::Scope::Builder::adoptBind( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>>&& value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::BIND); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>> Brand::Scope::Builder::disownBind() { + KJ_IREQUIRE((which() == Brand::Scope::BIND), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Brand::Scope::Reader::isInherit() const { + return which() == Brand::Scope::INHERIT; +} +inline bool Brand::Scope::Builder::isInherit() { + return which() == Brand::Scope::INHERIT; +} +inline ::capnp::Void Brand::Scope::Reader::getInherit() const { + KJ_IREQUIRE((which() == Brand::Scope::INHERIT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Brand::Scope::Builder::getInherit() { + KJ_IREQUIRE((which() == Brand::Scope::INHERIT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Brand::Scope::Builder::setInherit( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::INHERIT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::Brand::Binding::Which Brand::Binding::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Brand::Binding::Which Brand::Binding::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Brand::Binding::Reader::isUnbound() const { + return which() == Brand::Binding::UNBOUND; +} +inline bool Brand::Binding::Builder::isUnbound() { + return which() == Brand::Binding::UNBOUND; +} +inline ::capnp::Void Brand::Binding::Reader::getUnbound() const { + KJ_IREQUIRE((which() == Brand::Binding::UNBOUND), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Brand::Binding::Builder::getUnbound() { + KJ_IREQUIRE((which() == Brand::Binding::UNBOUND), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Brand::Binding::Builder::setUnbound( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::UNBOUND); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Brand::Binding::Reader::isType() const { + return which() == Brand::Binding::TYPE; +} +inline bool Brand::Binding::Builder::isType() { + return which() == Brand::Binding::TYPE; +} +inline bool Brand::Binding::Reader::hasType() const { + if (which() != Brand::Binding::TYPE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Brand::Binding::Builder::hasType() { + if (which() != Brand::Binding::TYPE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Brand::Binding::Reader::getType() const { + KJ_IREQUIRE((which() == Brand::Binding::TYPE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Brand::Binding::Builder::getType() { + KJ_IREQUIRE((which() == Brand::Binding::TYPE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Binding::Builder::setType( ::capnp::schema::Type::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::TYPE); + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Brand::Binding::Builder::initType() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::TYPE); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Binding::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::TYPE); + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Brand::Binding::Builder::disownType() { + KJ_IREQUIRE((which() == Brand::Binding::TYPE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Value::Which Value::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Value::Which Value::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Value::Reader::isVoid() const { + return which() == Value::VOID; +} +inline bool Value::Builder::isVoid() { + return which() == Value::VOID; +} +inline ::capnp::Void Value::Reader::getVoid() const { + KJ_IREQUIRE((which() == Value::VOID), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Value::Builder::getVoid() { + KJ_IREQUIRE((which() == Value::VOID), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setVoid( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::VOID); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isBool() const { + return which() == Value::BOOL; +} +inline bool Value::Builder::isBool() { + return which() == Value::BOOL; +} +inline bool Value::Reader::getBool() const { + KJ_IREQUIRE((which() == Value::BOOL), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} + +inline bool Value::Builder::getBool() { + KJ_IREQUIRE((which() == Value::BOOL), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setBool(bool value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::BOOL); + _builder.setDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt8() const { + return which() == Value::INT8; +} +inline bool Value::Builder::isInt8() { + return which() == Value::INT8; +} +inline ::int8_t Value::Reader::getInt8() const { + KJ_IREQUIRE((which() == Value::INT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::int8_t Value::Builder::getInt8() { + KJ_IREQUIRE((which() == Value::INT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt8( ::int8_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT8); + _builder.setDataField< ::int8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt16() const { + return which() == Value::INT16; +} +inline bool Value::Builder::isInt16() { + return which() == Value::INT16; +} +inline ::int16_t Value::Reader::getInt16() const { + KJ_IREQUIRE((which() == Value::INT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int16_t Value::Builder::getInt16() { + KJ_IREQUIRE((which() == Value::INT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt16( ::int16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT16); + _builder.setDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt32() const { + return which() == Value::INT32; +} +inline bool Value::Builder::isInt32() { + return which() == Value::INT32; +} +inline ::int32_t Value::Reader::getInt32() const { + KJ_IREQUIRE((which() == Value::INT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int32_t Value::Builder::getInt32() { + KJ_IREQUIRE((which() == Value::INT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt32( ::int32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT32); + _builder.setDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt64() const { + return which() == Value::INT64; +} +inline bool Value::Builder::isInt64() { + return which() == Value::INT64; +} +inline ::int64_t Value::Reader::getInt64() const { + KJ_IREQUIRE((which() == Value::INT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int64_t Value::Builder::getInt64() { + KJ_IREQUIRE((which() == Value::INT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt64( ::int64_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT64); + _builder.setDataField< ::int64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint8() const { + return which() == Value::UINT8; +} +inline bool Value::Builder::isUint8() { + return which() == Value::UINT8; +} +inline ::uint8_t Value::Reader::getUint8() const { + KJ_IREQUIRE((which() == Value::UINT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t Value::Builder::getUint8() { + KJ_IREQUIRE((which() == Value::UINT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint8( ::uint8_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT8); + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint16() const { + return which() == Value::UINT16; +} +inline bool Value::Builder::isUint16() { + return which() == Value::UINT16; +} +inline ::uint16_t Value::Reader::getUint16() const { + KJ_IREQUIRE((which() == Value::UINT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Value::Builder::getUint16() { + KJ_IREQUIRE((which() == Value::UINT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint16( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT16); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint32() const { + return which() == Value::UINT32; +} +inline bool Value::Builder::isUint32() { + return which() == Value::UINT32; +} +inline ::uint32_t Value::Reader::getUint32() const { + KJ_IREQUIRE((which() == Value::UINT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Value::Builder::getUint32() { + KJ_IREQUIRE((which() == Value::UINT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint32( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT32); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint64() const { + return which() == Value::UINT64; +} +inline bool Value::Builder::isUint64() { + return which() == Value::UINT64; +} +inline ::uint64_t Value::Reader::getUint64() const { + KJ_IREQUIRE((which() == Value::UINT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Value::Builder::getUint64() { + KJ_IREQUIRE((which() == Value::UINT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint64( ::uint64_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT64); + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isFloat32() const { + return which() == Value::FLOAT32; +} +inline bool Value::Builder::isFloat32() { + return which() == Value::FLOAT32; +} +inline float Value::Reader::getFloat32() const { + KJ_IREQUIRE((which() == Value::FLOAT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float Value::Builder::getFloat32() { + KJ_IREQUIRE((which() == Value::FLOAT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setFloat32(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::FLOAT32); + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isFloat64() const { + return which() == Value::FLOAT64; +} +inline bool Value::Builder::isFloat64() { + return which() == Value::FLOAT64; +} +inline double Value::Reader::getFloat64() const { + KJ_IREQUIRE((which() == Value::FLOAT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Value::Builder::getFloat64() { + KJ_IREQUIRE((which() == Value::FLOAT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setFloat64(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::FLOAT64); + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isText() const { + return which() == Value::TEXT; +} +inline bool Value::Builder::isText() { + return which() == Value::TEXT; +} +inline bool Value::Reader::hasText() const { + if (which() != Value::TEXT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasText() { + if (which() != Value::TEXT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Value::Reader::getText() const { + KJ_IREQUIRE((which() == Value::TEXT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Value::Builder::getText() { + KJ_IREQUIRE((which() == Value::TEXT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Value::Builder::setText( ::capnp::Text::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::TEXT); + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Value::Builder::initText(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::TEXT); + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Value::Builder::adoptText( + ::capnp::Orphan< ::capnp::Text>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::TEXT); + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Value::Builder::disownText() { + KJ_IREQUIRE((which() == Value::TEXT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Value::Reader::isData() const { + return which() == Value::DATA; +} +inline bool Value::Builder::isData() { + return which() == Value::DATA; +} +inline bool Value::Reader::hasData() const { + if (which() != Value::DATA) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasData() { + if (which() != Value::DATA) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader Value::Reader::getData() const { + KJ_IREQUIRE((which() == Value::DATA), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder Value::Builder::getData() { + KJ_IREQUIRE((which() == Value::DATA), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Value::Builder::setData( ::capnp::Data::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::DATA); + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder Value::Builder::initData(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::DATA); + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Value::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::DATA); + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> Value::Builder::disownData() { + KJ_IREQUIRE((which() == Value::DATA), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Value::Reader::isList() const { + return which() == Value::LIST; +} +inline bool Value::Builder::isList() { + return which() == Value::LIST; +} +inline bool Value::Reader::hasList() const { + if (which() != Value::LIST) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasList() { + if (which() != Value::LIST) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Value::Reader::getList() const { + KJ_IREQUIRE((which() == Value::LIST), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::getList() { + KJ_IREQUIRE((which() == Value::LIST), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::initList() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::LIST); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Value::Reader::isEnum() const { + return which() == Value::ENUM; +} +inline bool Value::Builder::isEnum() { + return which() == Value::ENUM; +} +inline ::uint16_t Value::Reader::getEnum() const { + KJ_IREQUIRE((which() == Value::ENUM), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Value::Builder::getEnum() { + KJ_IREQUIRE((which() == Value::ENUM), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setEnum( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::ENUM); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isStruct() const { + return which() == Value::STRUCT; +} +inline bool Value::Builder::isStruct() { + return which() == Value::STRUCT; +} +inline bool Value::Reader::hasStruct() const { + if (which() != Value::STRUCT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasStruct() { + if (which() != Value::STRUCT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Value::Reader::getStruct() const { + KJ_IREQUIRE((which() == Value::STRUCT), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::getStruct() { + KJ_IREQUIRE((which() == Value::STRUCT), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::initStruct() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::STRUCT); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Value::Reader::isInterface() const { + return which() == Value::INTERFACE; +} +inline bool Value::Builder::isInterface() { + return which() == Value::INTERFACE; +} +inline ::capnp::Void Value::Reader::getInterface() const { + KJ_IREQUIRE((which() == Value::INTERFACE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Value::Builder::getInterface() { + KJ_IREQUIRE((which() == Value::INTERFACE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInterface( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INTERFACE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isAnyPointer() const { + return which() == Value::ANY_POINTER; +} +inline bool Value::Builder::isAnyPointer() { + return which() == Value::ANY_POINTER; +} +inline bool Value::Reader::hasAnyPointer() const { + if (which() != Value::ANY_POINTER) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasAnyPointer() { + if (which() != Value::ANY_POINTER) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Value::Reader::getAnyPointer() const { + KJ_IREQUIRE((which() == Value::ANY_POINTER), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::getAnyPointer() { + KJ_IREQUIRE((which() == Value::ANY_POINTER), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::initAnyPointer() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::ANY_POINTER); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint64_t Annotation::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Annotation::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Annotation::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Annotation::Reader::hasValue() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Annotation::Builder::hasValue() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Value::Reader Annotation::Reader::getValue() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Value::Builder Annotation::Builder::getValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Value::Pipeline Annotation::Pipeline::getValue() { + return ::capnp::schema::Value::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Annotation::Builder::setValue( ::capnp::schema::Value::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Value::Builder Annotation::Builder::initValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Annotation::Builder::adoptValue( + ::capnp::Orphan< ::capnp::schema::Value>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Value> Annotation::Builder::disownValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Annotation::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Annotation::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Annotation::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Annotation::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Annotation::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Annotation::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Annotation::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Annotation::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Annotation::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint16_t CapnpVersion::Reader::getMajor() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t CapnpVersion::Builder::getMajor() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CapnpVersion::Builder::setMajor( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t CapnpVersion::Reader::getMinor() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t CapnpVersion::Builder::getMinor() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void CapnpVersion::Builder::setMinor( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t CapnpVersion::Reader::getMicro() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t CapnpVersion::Builder::getMicro() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void CapnpVersion::Builder::setMicro( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool CodeGeneratorRequest::Reader::hasNodes() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::Builder::hasNodes() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node>::Reader CodeGeneratorRequest::Reader::getNodes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node>::Builder CodeGeneratorRequest::Builder::getNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::Builder::setNodes( ::capnp::List< ::capnp::schema::Node>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node>::Builder CodeGeneratorRequest::Builder::initNodes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::Builder::adoptNodes( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>> CodeGeneratorRequest::Builder::disownNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool CodeGeneratorRequest::Reader::hasRequestedFiles() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::Builder::hasRequestedFiles() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader CodeGeneratorRequest::Reader::getRequestedFiles() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder CodeGeneratorRequest::Builder::getRequestedFiles() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::Builder::setRequestedFiles( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder CodeGeneratorRequest::Builder::initRequestedFiles(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::Builder::adoptRequestedFiles( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>> CodeGeneratorRequest::Builder::disownRequestedFiles() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool CodeGeneratorRequest::Reader::hasCapnpVersion() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::Builder::hasCapnpVersion() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::CapnpVersion::Reader CodeGeneratorRequest::Reader::getCapnpVersion() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::CapnpVersion::Builder CodeGeneratorRequest::Builder::getCapnpVersion() { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::CapnpVersion::Pipeline CodeGeneratorRequest::Pipeline::getCapnpVersion() { + return ::capnp::schema::CapnpVersion::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void CodeGeneratorRequest::Builder::setCapnpVersion( ::capnp::schema::CapnpVersion::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::CapnpVersion::Builder CodeGeneratorRequest::Builder::initCapnpVersion() { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::Builder::adoptCapnpVersion( + ::capnp::Orphan< ::capnp::schema::CapnpVersion>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::CapnpVersion> CodeGeneratorRequest::Builder::disownCapnpVersion() { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool CodeGeneratorRequest::RequestedFile::Reader::hasFilename() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::RequestedFile::Builder::hasFilename() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader CodeGeneratorRequest::RequestedFile::Reader::getFilename() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Builder::getFilename() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::setFilename( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Builder::initFilename(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::adoptFilename( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> CodeGeneratorRequest::RequestedFile::Builder::disownFilename() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool CodeGeneratorRequest::RequestedFile::Reader::hasImports() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::RequestedFile::Builder::hasImports() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader CodeGeneratorRequest::RequestedFile::Reader::getImports() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder CodeGeneratorRequest::RequestedFile::Builder::getImports() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::setImports( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder CodeGeneratorRequest::RequestedFile::Builder::initImports(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::adoptImports( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>> CodeGeneratorRequest::RequestedFile::Builder::disownImports() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Import::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Import::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CodeGeneratorRequest::RequestedFile::Import::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool CodeGeneratorRequest::RequestedFile::Import::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::RequestedFile::Import::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader CodeGeneratorRequest::RequestedFile::Import::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Import::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::RequestedFile::Import::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Import::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::RequestedFile::Import::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> CodeGeneratorRequest::RequestedFile::Import::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_a93fc509624c72d9_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema.h b/phonelibs/capnp-cpp/include/capnp/schema.h new file mode 100644 index 00000000000000..d59fa7523668d3 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema.h @@ -0,0 +1,934 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_H_ +#define CAPNP_SCHEMA_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#if CAPNP_LITE +#error "Reflection APIs, including this header, are not available in lite mode." +#endif + +#include + +namespace capnp { + +class Schema; +class StructSchema; +class EnumSchema; +class InterfaceSchema; +class ConstSchema; +class ListSchema; +class Type; + +template ()> struct SchemaType_ { typedef Schema Type; }; +template struct SchemaType_ { typedef schema::Type::Which Type; }; +template struct SchemaType_ { typedef schema::Type::Which Type; }; +template struct SchemaType_ { typedef EnumSchema Type; }; +template struct SchemaType_ { typedef StructSchema Type; }; +template struct SchemaType_ { typedef InterfaceSchema Type; }; +template struct SchemaType_ { typedef ListSchema Type; }; + +template +using SchemaType = typename SchemaType_::Type; +// SchemaType is the type of T's schema, e.g. StructSchema if T is a struct. + +namespace _ { // private +extern const RawSchema NULL_SCHEMA; +extern const RawSchema NULL_STRUCT_SCHEMA; +extern const RawSchema NULL_ENUM_SCHEMA; +extern const RawSchema NULL_INTERFACE_SCHEMA; +extern const RawSchema NULL_CONST_SCHEMA; +// The schema types default to these null (empty) schemas in case of error, especially when +// exceptions are disabled. +} // namespace _ (private) + +class Schema { + // Convenience wrapper around capnp::schema::Node. + +public: + inline Schema(): raw(&_::NULL_SCHEMA.defaultBrand) {} + + template + static inline SchemaType from() { return SchemaType::template fromImpl(); } + // Get the Schema for a particular compiled-in type. + + schema::Node::Reader getProto() const; + // Get the underlying Cap'n Proto representation of the schema node. (Note that this accessor + // has performance comparable to accessors of struct-typed fields on Reader classes.) + + kj::ArrayPtr asUncheckedMessage() const; + // Get the encoded schema node content as a single message segment. It is safe to read as an + // unchecked message. + + Schema getDependency(uint64_t id) const KJ_DEPRECATED("Does not handle generics correctly."); + // DEPRECATED: This method cannot correctly account for generic type parameter bindings that + // may apply to the dependency. Instead of using this method, use a method of the Schema API + // that corresponds to the exact kind of dependency. For example, to get a field type, use + // StructSchema::Field::getType(). + // + // Gets the Schema for one of this Schema's dependencies. For example, if this Schema is for a + // struct, you could look up the schema for one of its fields' types. Throws an exception if this + // schema doesn't actually depend on the given id. + // + // Note that not all type IDs found in the schema node are considered "dependencies" -- only the + // ones that are needed to implement the dynamic API are. That includes: + // - Field types. + // - Group types. + // - scopeId for group nodes, but NOT otherwise. + // - Method parameter and return types. + // + // The following are NOT considered dependencies: + // - Nested nodes. + // - scopeId for a non-group node. + // - Annotations. + // + // To obtain schemas for those, you would need a SchemaLoader. + + bool isBranded() const; + // Returns true if this schema represents a non-default parameterization of this type. + + Schema getGeneric() const; + // Get the version of this schema with any brands removed. + + class BrandArgumentList; + BrandArgumentList getBrandArgumentsAtScope(uint64_t scopeId) const; + // Gets the values bound to the brand parameters at the given scope. + + StructSchema asStruct() const; + EnumSchema asEnum() const; + InterfaceSchema asInterface() const; + ConstSchema asConst() const; + // Cast the Schema to a specific type. Throws an exception if the type doesn't match. Use + // getProto() to determine type, e.g. getProto().isStruct(). + + inline bool operator==(const Schema& other) const { return raw == other.raw; } + inline bool operator!=(const Schema& other) const { return raw != other.raw; } + // Determine whether two Schemas are wrapping the exact same underlying data, by identity. If + // you want to check if two Schemas represent the same type (but possibly different versions of + // it), compare their IDs instead. + + template + void requireUsableAs() const; + // Throws an exception if a value with this Schema cannot safely be cast to a native value of + // the given type. This passes if either: + // - *this == from() + // - This schema was loaded with SchemaLoader, the type ID matches typeId(), and + // loadCompiledTypeAndDependencies() was called on the SchemaLoader. + + kj::StringPtr getShortDisplayName() const; + // Get the short version of the node's display name. + +private: + const _::RawBrandedSchema* raw; + + inline explicit Schema(const _::RawBrandedSchema* raw): raw(raw) { + KJ_IREQUIRE(raw->lazyInitializer == nullptr, + "Must call ensureInitialized() on RawSchema before constructing Schema."); + } + + template static inline Schema fromImpl() { + return Schema(&_::rawSchema()); + } + + void requireUsableAs(const _::RawSchema* expected) const; + + uint32_t getSchemaOffset(const schema::Value::Reader& value) const; + + Type getBrandBinding(uint64_t scopeId, uint index) const; + // Look up the binding for a brand parameter used by this Schema. Returns `AnyPointer` if the + // parameter is not bound. + // + // TODO(someday): Public interface for iterating over all bindings? + + Schema getDependency(uint64_t id, uint location) const; + // Look up schema for a particular dependency of this schema. `location` is the dependency + // location number as defined in _::RawBrandedSchema. + + Type interpretType(schema::Type::Reader proto, uint location) const; + // Interpret a schema::Type in the given location within the schema, compiling it into a + // Type object. + + friend class StructSchema; + friend class EnumSchema; + friend class InterfaceSchema; + friend class ConstSchema; + friend class ListSchema; + friend class SchemaLoader; + friend class Type; + friend kj::StringTree _::structString( + _::StructReader reader, const _::RawBrandedSchema& schema); + friend kj::String _::enumString(uint16_t value, const _::RawBrandedSchema& schema); +}; + +kj::StringPtr KJ_STRINGIFY(const Schema& schema); + +class Schema::BrandArgumentList { + // A list of generic parameter bindings for parameters of some particular type. Note that since + // parameters on an outer type apply to all inner types as well, a deeply-nested type can have + // multiple BrandArgumentLists that apply to it. + // + // A BrandArgumentList only represents the arguments that the client of the type specified. Since + // new parameters can be added over time, this list may not cover all defined parameters for the + // type. Missing parameters should be treated as AnyPointer. This class's implementation of + // operator[] already does this for you; out-of-bounds access will safely return AnyPointer. + +public: + inline BrandArgumentList(): scopeId(0), size_(0), bindings(nullptr) {} + + inline uint size() const { return size_; } + Type operator[](uint index) const; + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + uint64_t scopeId; + uint size_; + bool isUnbound; + const _::RawBrandedSchema::Binding* bindings; + + inline BrandArgumentList(uint64_t scopeId, bool isUnbound) + : scopeId(scopeId), size_(0), isUnbound(isUnbound), bindings(nullptr) {} + inline BrandArgumentList(uint64_t scopeId, uint size, + const _::RawBrandedSchema::Binding* bindings) + : scopeId(scopeId), size_(size), isUnbound(false), bindings(bindings) {} + + friend class Schema; +}; + +// ------------------------------------------------------------------- + +class StructSchema: public Schema { +public: + inline StructSchema(): Schema(&_::NULL_STRUCT_SCHEMA.defaultBrand) {} + + class Field; + class FieldList; + class FieldSubset; + + FieldList getFields() const; + // List top-level fields of this struct. This list will contain top-level groups (including + // named unions) but not the members of those groups. The list does, however, contain the + // members of the unnamed union, if there is one. + + FieldSubset getUnionFields() const; + // If the field contains an unnamed union, get a list of fields in the union, ordered by + // ordinal. Since discriminant values are assigned sequentially by ordinal, you may index this + // list by discriminant value. + + FieldSubset getNonUnionFields() const; + // Get the fields of this struct which are not in an unnamed union, ordered by ordinal. + + kj::Maybe findFieldByName(kj::StringPtr name) const; + // Find the field with the given name, or return null if there is no such field. If the struct + // contains an unnamed union, then this will find fields of that union in addition to fields + // of the outer struct, since they exist in the same namespace. It will not, however, find + // members of groups (including named unions) -- you must first look up the group itself, + // then dig into its type. + + Field getFieldByName(kj::StringPtr name) const; + // Like findFieldByName() but throws an exception on failure. + + kj::Maybe getFieldByDiscriminant(uint16_t discriminant) const; + // Finds the field whose `discriminantValue` is equal to the given value, or returns null if + // there is no such field. (If the schema does not represent a union or a struct containing + // an unnamed union, then this always returns null.) + +private: + StructSchema(Schema base): Schema(base) {} + template static inline StructSchema fromImpl() { + return StructSchema(Schema(&_::rawBrandedSchema())); + } + friend class Schema; + friend class Type; +}; + +class StructSchema::Field { +public: + Field() = default; + + inline schema::Field::Reader getProto() const { return proto; } + inline StructSchema getContainingStruct() const { return parent; } + + inline uint getIndex() const { return index; } + // Get the index of this field within the containing struct or union. + + Type getType() const; + // Get the type of this field. Note that this is preferred over getProto().getType() as this + // method will apply generics. + + uint32_t getDefaultValueSchemaOffset() const; + // For struct, list, and object fields, returns the offset, in words, within the first segment of + // the struct's schema, where this field's default value pointer is located. The schema is + // always stored as a single-segment unchecked message, which in turn means that the default + // value pointer itself can be treated as the root of an unchecked message -- if you know where + // to find it, which is what this method helps you with. + // + // For blobs, returns the offset of the beginning of the blob's content within the first segment + // of the struct's schema. + // + // This is primarily useful for code generators. The C++ code generator, for example, embeds + // the entire schema as a raw word array within the generated code. Of course, to implement + // field accessors, it needs access to those fields' default values. Embedding separate copies + // of those default values would be redundant since they are already included in the schema, but + // seeking through the schema at runtime to find the default values would be ugly. Instead, + // the code generator can use getDefaultValueSchemaOffset() to find the offset of the default + // value within the schema, and can simply apply that offset at runtime. + // + // If the above does not make sense, you probably don't need this method. + + inline bool operator==(const Field& other) const; + inline bool operator!=(const Field& other) const { return !(*this == other); } + +private: + StructSchema parent; + uint index; + schema::Field::Reader proto; + + inline Field(StructSchema parent, uint index, schema::Field::Reader proto) + : parent(parent), index(index), proto(proto) {} + + friend class StructSchema; +}; + +kj::StringPtr KJ_STRINGIFY(const StructSchema::Field& field); + +class StructSchema::FieldList { +public: + FieldList() = default; // empty list + + inline uint size() const { return list.size(); } + inline Field operator[](uint index) const { return Field(parent, index, list[index]); } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + StructSchema parent; + List::Reader list; + + inline FieldList(StructSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class StructSchema; +}; + +class StructSchema::FieldSubset { +public: + FieldSubset() = default; // empty list + + inline uint size() const { return size_; } + inline Field operator[](uint index) const { + return Field(parent, indices[index], list[indices[index]]); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + StructSchema parent; + List::Reader list; + const uint16_t* indices; + uint size_; + + inline FieldSubset(StructSchema parent, List::Reader list, + const uint16_t* indices, uint size) + : parent(parent), list(list), indices(indices), size_(size) {} + + friend class StructSchema; +}; + +// ------------------------------------------------------------------- + +class EnumSchema: public Schema { +public: + inline EnumSchema(): Schema(&_::NULL_ENUM_SCHEMA.defaultBrand) {} + + class Enumerant; + class EnumerantList; + + EnumerantList getEnumerants() const; + + kj::Maybe findEnumerantByName(kj::StringPtr name) const; + + Enumerant getEnumerantByName(kj::StringPtr name) const; + // Like findEnumerantByName() but throws an exception on failure. + +private: + EnumSchema(Schema base): Schema(base) {} + template static inline EnumSchema fromImpl() { + return EnumSchema(Schema(&_::rawBrandedSchema())); + } + friend class Schema; + friend class Type; +}; + +class EnumSchema::Enumerant { +public: + Enumerant() = default; + + inline schema::Enumerant::Reader getProto() const { return proto; } + inline EnumSchema getContainingEnum() const { return parent; } + + inline uint16_t getOrdinal() const { return ordinal; } + inline uint getIndex() const { return ordinal; } + + inline bool operator==(const Enumerant& other) const; + inline bool operator!=(const Enumerant& other) const { return !(*this == other); } + +private: + EnumSchema parent; + uint16_t ordinal; + schema::Enumerant::Reader proto; + + inline Enumerant(EnumSchema parent, uint16_t ordinal, schema::Enumerant::Reader proto) + : parent(parent), ordinal(ordinal), proto(proto) {} + + friend class EnumSchema; +}; + +class EnumSchema::EnumerantList { +public: + EnumerantList() = default; // empty list + + inline uint size() const { return list.size(); } + inline Enumerant operator[](uint index) const { return Enumerant(parent, index, list[index]); } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + EnumSchema parent; + List::Reader list; + + inline EnumerantList(EnumSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class EnumSchema; +}; + +// ------------------------------------------------------------------- + +class InterfaceSchema: public Schema { +public: + inline InterfaceSchema(): Schema(&_::NULL_INTERFACE_SCHEMA.defaultBrand) {} + + class Method; + class MethodList; + + MethodList getMethods() const; + + kj::Maybe findMethodByName(kj::StringPtr name) const; + + Method getMethodByName(kj::StringPtr name) const; + // Like findMethodByName() but throws an exception on failure. + + class SuperclassList; + + SuperclassList getSuperclasses() const; + // Get the immediate superclasses of this type, after applying generics. + + bool extends(InterfaceSchema other) const; + // Returns true if `other` is a superclass of this interface (including if `other == *this`). + + kj::Maybe findSuperclass(uint64_t typeId) const; + // Find the superclass of this interface with the given type ID. Returns null if the interface + // extends no such type. + +private: + InterfaceSchema(Schema base): Schema(base) {} + template static inline InterfaceSchema fromImpl() { + return InterfaceSchema(Schema(&_::rawBrandedSchema())); + } + friend class Schema; + friend class Type; + + kj::Maybe findMethodByName(kj::StringPtr name, uint& counter) const; + bool extends(InterfaceSchema other, uint& counter) const; + kj::Maybe findSuperclass(uint64_t typeId, uint& counter) const; + // We protect against malicious schemas with large or cyclic hierarchies by cutting off the + // search when the counter reaches a threshold. +}; + +class InterfaceSchema::Method { +public: + Method() = default; + + inline schema::Method::Reader getProto() const { return proto; } + inline InterfaceSchema getContainingInterface() const { return parent; } + + inline uint16_t getOrdinal() const { return ordinal; } + inline uint getIndex() const { return ordinal; } + + StructSchema getParamType() const; + StructSchema getResultType() const; + // Get the parameter and result types, including substituting generic parameters. + + inline bool operator==(const Method& other) const; + inline bool operator!=(const Method& other) const { return !(*this == other); } + +private: + InterfaceSchema parent; + uint16_t ordinal; + schema::Method::Reader proto; + + inline Method(InterfaceSchema parent, uint16_t ordinal, + schema::Method::Reader proto) + : parent(parent), ordinal(ordinal), proto(proto) {} + + friend class InterfaceSchema; +}; + +class InterfaceSchema::MethodList { +public: + MethodList() = default; // empty list + + inline uint size() const { return list.size(); } + inline Method operator[](uint index) const { return Method(parent, index, list[index]); } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + InterfaceSchema parent; + List::Reader list; + + inline MethodList(InterfaceSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class InterfaceSchema; +}; + +class InterfaceSchema::SuperclassList { +public: + SuperclassList() = default; // empty list + + inline uint size() const { return list.size(); } + InterfaceSchema operator[](uint index) const; + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + InterfaceSchema parent; + List::Reader list; + + inline SuperclassList(InterfaceSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class InterfaceSchema; +}; + +// ------------------------------------------------------------------- + +class ConstSchema: public Schema { + // Represents a constant declaration. + // + // `ConstSchema` can be implicitly cast to DynamicValue to read its value. + +public: + inline ConstSchema(): Schema(&_::NULL_CONST_SCHEMA.defaultBrand) {} + + template + ReaderFor as() const; + // Read the constant's value. This is a convenience method equivalent to casting the ConstSchema + // to a DynamicValue and then calling its `as()` method. For dependency reasons, this method + // is defined in , which you must #include explicitly. + + uint32_t getValueSchemaOffset() const; + // Much like StructSchema::Field::getDefaultValueSchemaOffset(), if the constant has pointer + // type, this gets the offset from the beginning of the constant's schema node to a pointer + // representing the constant value. + + Type getType() const; + +private: + ConstSchema(Schema base): Schema(base) {} + friend class Schema; +}; + +// ------------------------------------------------------------------- + +class Type { +public: + struct BrandParameter { + uint64_t scopeId; + uint index; + }; + struct ImplicitParameter { + uint index; + }; + + inline Type(); + inline Type(schema::Type::Which primitive); + inline Type(StructSchema schema); + inline Type(EnumSchema schema); + inline Type(InterfaceSchema schema); + inline Type(ListSchema schema); + inline Type(schema::Type::AnyPointer::Unconstrained::Which anyPointerKind); + inline Type(BrandParameter param); + inline Type(ImplicitParameter param); + + template + inline static Type from(); + + inline schema::Type::Which which() const; + + StructSchema asStruct() const; + EnumSchema asEnum() const; + InterfaceSchema asInterface() const; + ListSchema asList() const; + // Each of these methods may only be called if which() returns the corresponding type. + + kj::Maybe getBrandParameter() const; + // Only callable if which() returns ANY_POINTER. Returns null if the type is just a regular + // AnyPointer and not a parameter. + + kj::Maybe getImplicitParameter() const; + // Only callable if which() returns ANY_POINTER. Returns null if the type is just a regular + // AnyPointer and not a parameter. "Implicit parameters" refer to type parameters on methods. + + inline schema::Type::AnyPointer::Unconstrained::Which whichAnyPointerKind() const; + // Only callable if which() returns ANY_POINTER. + + inline bool isVoid() const; + inline bool isBool() const; + inline bool isInt8() const; + inline bool isInt16() const; + inline bool isInt32() const; + inline bool isInt64() const; + inline bool isUInt8() const; + inline bool isUInt16() const; + inline bool isUInt32() const; + inline bool isUInt64() const; + inline bool isFloat32() const; + inline bool isFloat64() const; + inline bool isText() const; + inline bool isData() const; + inline bool isList() const; + inline bool isEnum() const; + inline bool isStruct() const; + inline bool isInterface() const; + inline bool isAnyPointer() const; + + bool operator==(const Type& other) const; + inline bool operator!=(const Type& other) const { return !(*this == other); } + + size_t hashCode() const; + + inline Type wrapInList(uint depth = 1) const; + // Return the Type formed by wrapping this type in List() `depth` times. + + inline Type(schema::Type::Which derived, const _::RawBrandedSchema* schema); + // For internal use. + +private: + schema::Type::Which baseType; // type not including applications of List() + uint8_t listDepth; // 0 for T, 1 for List(T), 2 for List(List(T)), ... + + bool isImplicitParam; + // If true, this refers to an implicit method parameter. baseType must be ANY_POINTER, scopeId + // must be zero, and paramIndex indicates the parameter index. + + union { + uint16_t paramIndex; + // If baseType is ANY_POINTER but this Type actually refers to a type parameter, this is the + // index of the parameter among the parameters at its scope, and `scopeId` below is the type ID + // of the scope where the parameter was defined. + + schema::Type::AnyPointer::Unconstrained::Which anyPointerKind; + // If scopeId is zero and isImplicitParam is false. + }; + + union { + const _::RawBrandedSchema* schema; // if type is struct, enum, interface... + uint64_t scopeId; // if type is AnyPointer but it's actually a type parameter... + }; + + Type(schema::Type::Which baseType, uint8_t listDepth, const _::RawBrandedSchema* schema) + : baseType(baseType), listDepth(listDepth), schema(schema) { + KJ_IREQUIRE(baseType != schema::Type::ANY_POINTER); + } + + void requireUsableAs(Type expected) const; + + friend class ListSchema; // only for requireUsableAs() +}; + +// ------------------------------------------------------------------- + +class ListSchema { + // ListSchema is a little different because list types are not described by schema nodes. So, + // ListSchema doesn't subclass Schema. + +public: + ListSchema() = default; + + static ListSchema of(schema::Type::Which primitiveType); + static ListSchema of(StructSchema elementType); + static ListSchema of(EnumSchema elementType); + static ListSchema of(InterfaceSchema elementType); + static ListSchema of(ListSchema elementType); + static ListSchema of(Type elementType); + // Construct the schema for a list of the given type. + + static ListSchema of(schema::Type::Reader elementType, Schema context) + KJ_DEPRECATED("Does not handle generics correctly."); + // DEPRECATED: This method cannot correctly account for generic type parameter bindings that + // may apply to the input type. Instead of using this method, use a method of the Schema API + // that corresponds to the exact kind of dependency. For example, to get a field type, use + // StructSchema::Field::getType(). + // + // Construct from an element type schema. Requires a context which can handle getDependency() + // requests for any type ID found in the schema. + + Type getElementType() const; + + inline schema::Type::Which whichElementType() const; + // Get the element type's "which()". ListSchema does not actually store a schema::Type::Reader + // describing the element type, but if it did, this would be equivalent to calling + // .getBody().which() on that type. + + StructSchema getStructElementType() const; + EnumSchema getEnumElementType() const; + InterfaceSchema getInterfaceElementType() const; + ListSchema getListElementType() const; + // Get the schema for complex element types. Each of these throws an exception if the element + // type is not of the requested kind. + + inline bool operator==(const ListSchema& other) const { return elementType == other.elementType; } + inline bool operator!=(const ListSchema& other) const { return elementType != other.elementType; } + + template + void requireUsableAs() const; + +private: + Type elementType; + + inline explicit ListSchema(Type elementType): elementType(elementType) {} + + template + struct FromImpl; + template static inline ListSchema fromImpl() { + return FromImpl::get(); + } + + void requireUsableAs(ListSchema expected) const; + + friend class Schema; +}; + +// ======================================================================================= +// inline implementation + +template <> inline schema::Type::Which Schema::from() { return schema::Type::VOID; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::BOOL; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT8; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT16; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT32; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT64; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT8; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT16; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT32; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT64; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::FLOAT32; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::FLOAT64; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::TEXT; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::DATA; } + +inline Schema Schema::getDependency(uint64_t id) const { + return getDependency(id, 0); +} + +inline bool Schema::isBranded() const { + return raw != &raw->generic->defaultBrand; +} + +inline Schema Schema::getGeneric() const { + return Schema(&raw->generic->defaultBrand); +} + +template +inline void Schema::requireUsableAs() const { + requireUsableAs(&_::rawSchema()); +} + +inline bool StructSchema::Field::operator==(const Field& other) const { + return parent == other.parent && index == other.index; +} +inline bool EnumSchema::Enumerant::operator==(const Enumerant& other) const { + return parent == other.parent && ordinal == other.ordinal; +} +inline bool InterfaceSchema::Method::operator==(const Method& other) const { + return parent == other.parent && ordinal == other.ordinal; +} + +inline ListSchema ListSchema::of(StructSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(EnumSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(InterfaceSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(ListSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(Type elementType) { + return ListSchema(elementType); +} + +inline Type ListSchema::getElementType() const { + return elementType; +} + +inline schema::Type::Which ListSchema::whichElementType() const { + return elementType.which(); +} + +inline StructSchema ListSchema::getStructElementType() const { + return elementType.asStruct(); +} + +inline EnumSchema ListSchema::getEnumElementType() const { + return elementType.asEnum(); +} + +inline InterfaceSchema ListSchema::getInterfaceElementType() const { + return elementType.asInterface(); +} + +inline ListSchema ListSchema::getListElementType() const { + return elementType.asList(); +} + +template +inline void ListSchema::requireUsableAs() const { + static_assert(kind() == Kind::LIST, + "ListSchema::requireUsableAs() requires T is a list type."); + requireUsableAs(Schema::from()); +} + +inline void ListSchema::requireUsableAs(ListSchema expected) const { + elementType.requireUsableAs(expected.elementType); +} + +template +struct ListSchema::FromImpl> { + static inline ListSchema get() { return of(Schema::from()); } +}; + +inline Type::Type(): baseType(schema::Type::VOID), listDepth(0), schema(nullptr) {} +inline Type::Type(schema::Type::Which primitive) + : baseType(primitive), listDepth(0), isImplicitParam(false) { + KJ_IREQUIRE(primitive != schema::Type::STRUCT && + primitive != schema::Type::ENUM && + primitive != schema::Type::INTERFACE && + primitive != schema::Type::LIST); + if (primitive == schema::Type::ANY_POINTER) { + scopeId = 0; + anyPointerKind = schema::Type::AnyPointer::Unconstrained::ANY_KIND; + } else { + schema = nullptr; + } +} +inline Type::Type(schema::Type::Which derived, const _::RawBrandedSchema* schema) + : baseType(derived), listDepth(0), isImplicitParam(false), schema(schema) { + KJ_IREQUIRE(derived == schema::Type::STRUCT || + derived == schema::Type::ENUM || + derived == schema::Type::INTERFACE); +} + +inline Type::Type(StructSchema schema) + : baseType(schema::Type::STRUCT), listDepth(0), schema(schema.raw) {} +inline Type::Type(EnumSchema schema) + : baseType(schema::Type::ENUM), listDepth(0), schema(schema.raw) {} +inline Type::Type(InterfaceSchema schema) + : baseType(schema::Type::INTERFACE), listDepth(0), schema(schema.raw) {} +inline Type::Type(ListSchema schema) + : Type(schema.getElementType()) { ++listDepth; } +inline Type::Type(schema::Type::AnyPointer::Unconstrained::Which anyPointerKind) + : baseType(schema::Type::ANY_POINTER), listDepth(0), isImplicitParam(false), + anyPointerKind(anyPointerKind), scopeId(0) {} +inline Type::Type(BrandParameter param) + : baseType(schema::Type::ANY_POINTER), listDepth(0), isImplicitParam(false), + paramIndex(param.index), scopeId(param.scopeId) {} +inline Type::Type(ImplicitParameter param) + : baseType(schema::Type::ANY_POINTER), listDepth(0), isImplicitParam(true), + paramIndex(param.index), scopeId(0) {} + +inline schema::Type::Which Type::which() const { + return listDepth > 0 ? schema::Type::LIST : baseType; +} + +inline schema::Type::AnyPointer::Unconstrained::Which Type::whichAnyPointerKind() const { + KJ_IREQUIRE(baseType == schema::Type::ANY_POINTER); + return !isImplicitParam && scopeId == 0 ? anyPointerKind + : schema::Type::AnyPointer::Unconstrained::ANY_KIND; +} + +template +inline Type Type::from() { return Type(Schema::from()); } + +inline bool Type::isVoid () const { return baseType == schema::Type::VOID && listDepth == 0; } +inline bool Type::isBool () const { return baseType == schema::Type::BOOL && listDepth == 0; } +inline bool Type::isInt8 () const { return baseType == schema::Type::INT8 && listDepth == 0; } +inline bool Type::isInt16 () const { return baseType == schema::Type::INT16 && listDepth == 0; } +inline bool Type::isInt32 () const { return baseType == schema::Type::INT32 && listDepth == 0; } +inline bool Type::isInt64 () const { return baseType == schema::Type::INT64 && listDepth == 0; } +inline bool Type::isUInt8 () const { return baseType == schema::Type::UINT8 && listDepth == 0; } +inline bool Type::isUInt16 () const { return baseType == schema::Type::UINT16 && listDepth == 0; } +inline bool Type::isUInt32 () const { return baseType == schema::Type::UINT32 && listDepth == 0; } +inline bool Type::isUInt64 () const { return baseType == schema::Type::UINT64 && listDepth == 0; } +inline bool Type::isFloat32() const { return baseType == schema::Type::FLOAT32 && listDepth == 0; } +inline bool Type::isFloat64() const { return baseType == schema::Type::FLOAT64 && listDepth == 0; } +inline bool Type::isText () const { return baseType == schema::Type::TEXT && listDepth == 0; } +inline bool Type::isData () const { return baseType == schema::Type::DATA && listDepth == 0; } +inline bool Type::isList () const { return listDepth > 0; } +inline bool Type::isEnum () const { return baseType == schema::Type::ENUM && listDepth == 0; } +inline bool Type::isStruct () const { return baseType == schema::Type::STRUCT && listDepth == 0; } +inline bool Type::isInterface() const { + return baseType == schema::Type::INTERFACE && listDepth == 0; +} +inline bool Type::isAnyPointer() const { + return baseType == schema::Type::ANY_POINTER && listDepth == 0; +} + +inline Type Type::wrapInList(uint depth) const { + Type result = *this; + result.listDepth += depth; + return result; +} + +} // namespace capnp + +#endif // CAPNP_SCHEMA_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize-async.h b/phonelibs/capnp-cpp/include/capnp/serialize-async.h new file mode 100644 index 00000000000000..a16bfd8975a6c7 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize-async.h @@ -0,0 +1,64 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SERIALIZE_ASYNC_H_ +#define CAPNP_SERIALIZE_ASYNC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include "message.h" + +namespace capnp { + +kj::Promise> readMessage( + kj::AsyncInputStream& input, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Read a message asynchronously. +// +// `input` must remain valid until the returned promise resolves (or is canceled). +// +// `scratchSpace`, if provided, must remain valid until the returned MessageReader is destroyed. + +kj::Promise>> tryReadMessage( + kj::AsyncInputStream& input, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Like `readMessage` but returns null on EOF. + +kj::Promise writeMessage(kj::AsyncOutputStream& output, + kj::ArrayPtr> segments) + KJ_WARN_UNUSED_RESULT; +kj::Promise writeMessage(kj::AsyncOutputStream& output, MessageBuilder& builder) + KJ_WARN_UNUSED_RESULT; +// Write asynchronously. The parameters must remain valid until the returned promise resolves. + +// ======================================================================================= +// inline implementation details + +inline kj::Promise writeMessage(kj::AsyncOutputStream& output, MessageBuilder& builder) { + return writeMessage(output, builder.getSegmentsForOutput()); +} + +} // namespace capnp + +#endif // CAPNP_SERIALIZE_ASYNC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize-packed.h b/phonelibs/capnp-cpp/include/capnp/serialize-packed.h new file mode 100644 index 00000000000000..a71260ce1dd4c1 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize-packed.h @@ -0,0 +1,130 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SERIALIZE_PACKED_H_ +#define CAPNP_SERIALIZE_PACKED_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "serialize.h" + +namespace capnp { + +namespace _ { // private + +class PackedInputStream: public kj::InputStream { + // An input stream that unpacks packed data with a picky constraint: The caller must read data + // in the exact same size and sequence as the data was written to PackedOutputStream. + +public: + explicit PackedInputStream(kj::BufferedInputStream& inner); + KJ_DISALLOW_COPY(PackedInputStream); + ~PackedInputStream() noexcept(false); + + // implements InputStream ------------------------------------------ + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + void skip(size_t bytes) override; + +private: + kj::BufferedInputStream& inner; +}; + +class PackedOutputStream: public kj::OutputStream { +public: + explicit PackedOutputStream(kj::BufferedOutputStream& inner); + KJ_DISALLOW_COPY(PackedOutputStream); + ~PackedOutputStream() noexcept(false); + + // implements OutputStream ----------------------------------------- + void write(const void* buffer, size_t bytes) override; + +private: + kj::BufferedOutputStream& inner; +}; + +} // namespace _ (private) + +class PackedMessageReader: private _::PackedInputStream, public InputStreamMessageReader { +public: + PackedMessageReader(kj::BufferedInputStream& inputStream, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + KJ_DISALLOW_COPY(PackedMessageReader); + ~PackedMessageReader() noexcept(false); +}; + +class PackedFdMessageReader: private kj::FdInputStream, private kj::BufferedInputStreamWrapper, + public PackedMessageReader { +public: + PackedFdMessageReader(int fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + // Read message from a file descriptor, without taking ownership of the descriptor. + // Note that if you want to reuse the descriptor after the reader is destroyed, you'll need to + // seek it, since otherwise the position is unspecified. + + PackedFdMessageReader(kj::AutoCloseFd fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + // Read a message from a file descriptor, taking ownership of the descriptor. + + KJ_DISALLOW_COPY(PackedFdMessageReader); + + ~PackedFdMessageReader() noexcept(false); +}; + +void writePackedMessage(kj::BufferedOutputStream& output, MessageBuilder& builder); +void writePackedMessage(kj::BufferedOutputStream& output, + kj::ArrayPtr> segments); +// Write a packed message to a buffered output stream. + +void writePackedMessage(kj::OutputStream& output, MessageBuilder& builder); +void writePackedMessage(kj::OutputStream& output, + kj::ArrayPtr> segments); +// Write a packed message to an unbuffered output stream. If you intend to write multiple messages +// in succession, consider wrapping your output in a buffered stream in order to reduce system +// call overhead. + +void writePackedMessageToFd(int fd, MessageBuilder& builder); +void writePackedMessageToFd(int fd, kj::ArrayPtr> segments); +// Write a single packed message to the file descriptor. + +size_t computeUnpackedSizeInWords(kj::ArrayPtr packedBytes); +// Computes the number of words to which the given packed bytes will unpack. Not intended for use +// in performance-sensitive situations. + +// ======================================================================================= +// inline stuff + +inline void writePackedMessage(kj::BufferedOutputStream& output, MessageBuilder& builder) { + writePackedMessage(output, builder.getSegmentsForOutput()); +} + +inline void writePackedMessage(kj::OutputStream& output, MessageBuilder& builder) { + writePackedMessage(output, builder.getSegmentsForOutput()); +} + +inline void writePackedMessageToFd(int fd, MessageBuilder& builder) { + writePackedMessageToFd(fd, builder.getSegmentsForOutput()); +} + +} // namespace capnp + +#endif // CAPNP_SERIALIZE_PACKED_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize-text.h b/phonelibs/capnp-cpp/include/capnp/serialize-text.h new file mode 100644 index 00000000000000..d86fc2c00ec8a5 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize-text.h @@ -0,0 +1,96 @@ +// Copyright (c) 2015 Philip Quinn. +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SERIALIZE_TEXT_H_ +#define CAPNP_SERIALIZE_TEXT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include "dynamic.h" +#include "orphan.h" +#include "schema.h" + +namespace capnp { + +class TextCodec { + // Reads and writes Cap'n Proto objects in a plain text format (as used in the schema + // language for constants, and read/written by the 'decode' and 'encode' commands of + // the capnp tool). + // + // This format is useful for debugging or human input, but it is not a robust alternative + // to the binary format. Changes to a schema's types or names that are permitted in a + // schema's binary evolution will likely break messages stored in this format. + // + // Note that definitions or references (to constants, other fields, or files) are not + // permitted in this format. To evaluate declarations with the full expressiveness of the + // schema language, see `capnp::SchemaParser`. + // + // Requires linking with the capnpc library. + +public: + TextCodec(); + ~TextCodec() noexcept(true); + + void setPrettyPrint(bool enabled); + // If enabled, pads the output of `encode()` with spaces and newlines to make it more + // human-readable. + + template + kj::String encode(T&& value) const; + kj::String encode(DynamicValue::Reader value) const; + // Encode any Cap'n Proto value. + + template + Orphan decode(kj::StringPtr input, Orphanage orphanage) const; + // Decode a text message into a Cap'n Proto object of type T, allocated in the given + // orphanage. Any errors parsing the input or assigning the fields of T are thrown as + // exceptions. + + void decode(kj::StringPtr input, DynamicStruct::Builder output) const; + // Decode a text message for a struct into the given builder. Any errors parsing the + // input or assigning the fields of the output are thrown as exceptions. + + // TODO(someday): expose some control over the error handling? +private: + Orphan decode(kj::StringPtr input, Type type, Orphanage orphanage) const; + + bool prettyPrint; +}; + +// ======================================================================================= +// inline stuff + +template +inline kj::String TextCodec::encode(T&& value) const { + return encode(DynamicValue::Reader(ReaderFor>(kj::fwd(value)))); +} + +template +inline Orphan TextCodec::decode(kj::StringPtr input, Orphanage orphanage) const { + return decode(input, Type::from(), orphanage).template releaseAs(); +} + +} // namespace capnp + +#endif // CAPNP_SERIALIZE_TEXT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize.h b/phonelibs/capnp-cpp/include/capnp/serialize.h new file mode 100644 index 00000000000000..797db517662abd --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize.h @@ -0,0 +1,237 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file implements a simple serialization format for Cap'n Proto messages. The format +// is as follows: +// +// * 32-bit little-endian segment count (4 bytes). +// * 32-bit little-endian size of each segment (4*(segment count) bytes). +// * Padding so that subsequent data is 64-bit-aligned (0 or 4 bytes). (I.e., if there are an even +// number of segments, there are 4 bytes of zeros here, otherwise there is no padding.) +// * Data from each segment, in order (8*sum(segment sizes) bytes) +// +// This format has some important properties: +// - It is self-delimiting, so multiple messages may be written to a stream without any external +// delimiter. +// - The total size and position of each segment can be determined by reading only the first part +// of the message, allowing lazy and random-access reading of the segment data. +// - A message is always at least 8 bytes. +// - A single-segment message can be read entirely in two system calls with no buffering. +// - A multi-segment message can be read entirely in three system calls with no buffering. +// - The format is appropriate for mmap()ing since all data is aligned. + +#ifndef CAPNP_SERIALIZE_H_ +#define CAPNP_SERIALIZE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "message.h" +#include + +namespace capnp { + +class FlatArrayMessageReader: public MessageReader { + // Parses a message from a flat array. Note that it makes sense to use this together with mmap() + // for extremely fast parsing. + +public: + FlatArrayMessageReader(kj::ArrayPtr array, ReaderOptions options = ReaderOptions()); + // The array must remain valid until the MessageReader is destroyed. + + kj::ArrayPtr getSegment(uint id) override; + + const word* getEnd() const { return end; } + // Get a pointer just past the end of the message as determined by reading the message header. + // This could actually be before the end of the input array. This pointer is useful e.g. if + // you know that the input array has extra stuff appended after the message and you want to + // get at it. + +private: + // Optimize for single-segment case. + kj::ArrayPtr segment0; + kj::Array> moreSegments; + const word* end; +}; + +kj::ArrayPtr initMessageBuilderFromFlatArrayCopy( + kj::ArrayPtr array, MessageBuilder& target, + ReaderOptions options = ReaderOptions()); +// Convenience function which reads a message using `FlatArrayMessageReader` then copies the +// content into the target `MessageBuilder`, verifying that the message structure is valid +// (although not necessarily that it matches the desired schema). +// +// Returns an ArrayPtr containing any words left over in the array after consuming the whole +// message. This is useful when reading multiple messages that have been concatenated. See also +// FlatArrayMessageReader::getEnd(). +// +// (Note that it's also possible to initialize a `MessageBuilder` directly without a copy using one +// of `MessageBuilder`'s constructors. However, this approach skips the validation step and is not +// safe to use on untrusted input. Therefore, we do not provide a convenience method for it.) + +kj::Array messageToFlatArray(MessageBuilder& builder); +// Constructs a flat array containing the entire content of the given message. +// +// To output the message as bytes, use `.asBytes()` on the returned word array. Keep in mind that +// `asBytes()` returns an ArrayPtr, so you have to save the Array as well to prevent it from being +// deleted. For example: +// +// kj::Array words = messageToFlatArray(myMessage); +// kj::ArrayPtr bytes = words.asBytes(); +// write(fd, bytes.begin(), bytes.size()); + +kj::Array messageToFlatArray(kj::ArrayPtr> segments); +// Version of messageToFlatArray that takes a raw segment array. + +size_t computeSerializedSizeInWords(MessageBuilder& builder); +// Returns the size, in words, that will be needed to serialize the message, including the header. + +size_t computeSerializedSizeInWords(kj::ArrayPtr> segments); +// Version of computeSerializedSizeInWords that takes a raw segment array. + +size_t expectedSizeInWordsFromPrefix(kj::ArrayPtr messagePrefix); +// Given a prefix of a serialized message, try to determine the expected total size of the message, +// in words. The returned size is based on the information known so far; it may be an underestimate +// if the prefix doesn't contain the full segment table. +// +// If the returned value is greater than `messagePrefix.size()`, then the message is not yet +// complete and the app cannot parse it yet. If the returned value is less than or equal to +// `messagePrefix.size()`, then the returned value is the exact total size of the message; any +// remaining bytes are part of the next message. +// +// This function is useful when reading messages from a stream in an asynchronous way, but when +// using the full KJ async infrastructure would be too difficult. Each time bytes are received, +// use this function to determine if an entire message is ready to be parsed. + +// ======================================================================================= + +class InputStreamMessageReader: public MessageReader { + // A MessageReader that reads from an abstract kj::InputStream. See also StreamFdMessageReader + // for a subclass specific to file descriptors. + +public: + InputStreamMessageReader(kj::InputStream& inputStream, + ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + ~InputStreamMessageReader() noexcept(false); + + // implements MessageReader ---------------------------------------- + kj::ArrayPtr getSegment(uint id) override; + +private: + kj::InputStream& inputStream; + byte* readPos; + + // Optimize for single-segment case. + kj::ArrayPtr segment0; + kj::Array> moreSegments; + + kj::Array ownedSpace; + // Only if scratchSpace wasn't big enough. + + kj::UnwindDetector unwindDetector; +}; + +void readMessageCopy(kj::InputStream& input, MessageBuilder& target, + ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Convenience function which reads a message using `InputStreamMessageReader` then copies the +// content into the target `MessageBuilder`, verifying that the message structure is valid +// (although not necessarily that it matches the desired schema). +// +// (Note that it's also possible to initialize a `MessageBuilder` directly without a copy using one +// of `MessageBuilder`'s constructors. However, this approach skips the validation step and is not +// safe to use on untrusted input. Therefore, we do not provide a convenience method for it.) + +void writeMessage(kj::OutputStream& output, MessageBuilder& builder); +// Write the message to the given output stream. + +void writeMessage(kj::OutputStream& output, kj::ArrayPtr> segments); +// Write the segment array to the given output stream. + +// ======================================================================================= +// Specializations for reading from / writing to file descriptors. + +class StreamFdMessageReader: private kj::FdInputStream, public InputStreamMessageReader { + // A MessageReader that reads from a steam-based file descriptor. + +public: + StreamFdMessageReader(int fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr) + : FdInputStream(fd), InputStreamMessageReader(*this, options, scratchSpace) {} + // Read message from a file descriptor, without taking ownership of the descriptor. + + StreamFdMessageReader(kj::AutoCloseFd fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr) + : FdInputStream(kj::mv(fd)), InputStreamMessageReader(*this, options, scratchSpace) {} + // Read a message from a file descriptor, taking ownership of the descriptor. + + ~StreamFdMessageReader() noexcept(false); +}; + +void readMessageCopyFromFd(int fd, MessageBuilder& target, + ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Convenience function which reads a message using `StreamFdMessageReader` then copies the +// content into the target `MessageBuilder`, verifying that the message structure is valid +// (although not necessarily that it matches the desired schema). +// +// (Note that it's also possible to initialize a `MessageBuilder` directly without a copy using one +// of `MessageBuilder`'s constructors. However, this approach skips the validation step and is not +// safe to use on untrusted input. Therefore, we do not provide a convenience method for it.) + +void writeMessageToFd(int fd, MessageBuilder& builder); +// Write the message to the given file descriptor. +// +// This function throws an exception on any I/O error. If your code is not exception-safe, be sure +// you catch this exception at the call site. If throwing an exception is not acceptable, you +// can implement your own OutputStream with arbitrary error handling and then use writeMessage(). + +void writeMessageToFd(int fd, kj::ArrayPtr> segments); +// Write the segment array to the given file descriptor. +// +// This function throws an exception on any I/O error. If your code is not exception-safe, be sure +// you catch this exception at the call site. If throwing an exception is not acceptable, you +// can implement your own OutputStream with arbitrary error handling and then use writeMessage(). + +// ======================================================================================= +// inline stuff + +inline kj::Array messageToFlatArray(MessageBuilder& builder) { + return messageToFlatArray(builder.getSegmentsForOutput()); +} + +inline size_t computeSerializedSizeInWords(MessageBuilder& builder) { + return computeSerializedSizeInWords(builder.getSegmentsForOutput()); +} + +inline void writeMessage(kj::OutputStream& output, MessageBuilder& builder) { + writeMessage(output, builder.getSegmentsForOutput()); +} + +inline void writeMessageToFd(int fd, MessageBuilder& builder) { + writeMessageToFd(fd, builder.getSegmentsForOutput()); +} + +} // namespace capnp + +#endif // SERIALIZE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/arena.h b/phonelibs/capnp-cpp/include/kj/arena.h new file mode 100644 index 00000000000000..32c1f61c51626f --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/arena.h @@ -0,0 +1,213 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ARENA_H_ +#define KJ_ARENA_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" +#include "array.h" +#include "string.h" + +namespace kj { + +class Arena { + // A class which allows several objects to be allocated in contiguous chunks of memory, then + // frees them all at once. + // + // Allocating from the same Arena in multiple threads concurrently is NOT safe, because making + // it safe would require atomic operations that would slow down allocation even when + // single-threaded. If you need to use arena allocation in a multithreaded context, consider + // allocating thread-local arenas. + +public: + explicit Arena(size_t chunkSizeHint = 1024); + // Create an Arena. `chunkSizeHint` hints at where to start when allocating chunks, but is only + // a hint -- the Arena will, for example, allocate progressively larger chunks as time goes on, + // in order to reduce overall allocation overhead. + + explicit Arena(ArrayPtr scratch); + // Allocates from the given scratch space first, only resorting to the heap when it runs out. + + KJ_DISALLOW_COPY(Arena); + ~Arena() noexcept(false); + + template + T& allocate(Params&&... params); + template + ArrayPtr allocateArray(size_t size); + // Allocate an object or array of type T. If T has a non-trivial destructor, that destructor + // will be run during the Arena's destructor. Such destructors are run in opposite order of + // allocation. Note that these methods must maintain a list of destructors to call, which has + // overhead, but this overhead only applies if T has a non-trivial destructor. + + template + Own allocateOwn(Params&&... params); + template + Array allocateOwnArray(size_t size); + template + ArrayBuilder allocateOwnArrayBuilder(size_t capacity); + // Allocate an object or array of type T. Destructors are executed when the returned Own + // or Array goes out-of-scope, which must happen before the Arena is destroyed. This variant + // is useful when you need to control when the destructor is called. This variant also avoids + // the need for the Arena itself to keep track of destructors to call later, which may make it + // slightly more efficient. + + template + inline T& copy(T&& value) { return allocate>(kj::fwd(value)); } + // Allocate a copy of the given value in the arena. This is just a shortcut for calling the + // type's copy (or move) constructor. + + StringPtr copyString(StringPtr content); + // Make a copy of the given string inside the arena, and return a pointer to the copy. + +private: + struct ChunkHeader { + ChunkHeader* next; + byte* pos; // first unallocated byte in this chunk + byte* end; // end of this chunk + }; + struct ObjectHeader { + void (*destructor)(void*); + ObjectHeader* next; + }; + + size_t nextChunkSize; + ChunkHeader* chunkList = nullptr; + ObjectHeader* objectList = nullptr; + + ChunkHeader* currentChunk = nullptr; + + void cleanup(); + // Run all destructors, leaving the above pointers null. If a destructor throws, the State is + // left in a consistent state, such that if cleanup() is called again, it will pick up where + // it left off. + + void* allocateBytes(size_t amount, uint alignment, bool hasDisposer); + // Allocate the given number of bytes. `hasDisposer` must be true if `setDisposer()` may be + // called on this pointer later. + + void* allocateBytesInternal(size_t amount, uint alignment); + // Try to allocate the given number of bytes without taking a lock. Fails if and only if there + // is no space left in the current chunk. + + void setDestructor(void* ptr, void (*destructor)(void*)); + // Schedule the given destructor to be executed when the Arena is destroyed. `ptr` must be a + // pointer previously returned by an `allocateBytes()` call for which `hasDisposer` was true. + + template + static void destroyArray(void* pointer) { + size_t elementCount = *reinterpret_cast(pointer); + constexpr size_t prefixSize = kj::max(alignof(T), sizeof(size_t)); + DestructorOnlyArrayDisposer::instance.disposeImpl( + reinterpret_cast(pointer) + prefixSize, + sizeof(T), elementCount, elementCount, &destroyObject); + } + + template + static void destroyObject(void* pointer) { + dtor(*reinterpret_cast(pointer)); + } +}; + +// ======================================================================================= +// Inline implementation details + +template +T& Arena::allocate(Params&&... params) { + T& result = *reinterpret_cast(allocateBytes( + sizeof(T), alignof(T), !__has_trivial_destructor(T))); + if (!__has_trivial_constructor(T) || sizeof...(Params) > 0) { + ctor(result, kj::fwd(params)...); + } + if (!__has_trivial_destructor(T)) { + setDestructor(&result, &destroyObject); + } + return result; +} + +template +ArrayPtr Arena::allocateArray(size_t size) { + if (__has_trivial_destructor(T)) { + ArrayPtr result = + arrayPtr(reinterpret_cast(allocateBytes( + sizeof(T) * size, alignof(T), false)), size); + if (!__has_trivial_constructor(T)) { + for (size_t i = 0; i < size; i++) { + ctor(result[i]); + } + } + return result; + } else { + // Allocate with a 64-bit prefix in which we store the array size. + constexpr size_t prefixSize = kj::max(alignof(T), sizeof(size_t)); + void* base = allocateBytes(sizeof(T) * size + prefixSize, alignof(T), true); + size_t& tag = *reinterpret_cast(base); + ArrayPtr result = + arrayPtr(reinterpret_cast(reinterpret_cast(base) + prefixSize), size); + setDestructor(base, &destroyArray); + + if (__has_trivial_constructor(T)) { + tag = size; + } else { + // In case of constructor exceptions, we need the tag to end up storing the number of objects + // that were successfully constructed, so that they'll be properly destroyed. + tag = 0; + for (size_t i = 0; i < size; i++) { + ctor(result[i]); + tag = i + 1; + } + } + return result; + } +} + +template +Own Arena::allocateOwn(Params&&... params) { + T& result = *reinterpret_cast(allocateBytes(sizeof(T), alignof(T), false)); + if (!__has_trivial_constructor(T) || sizeof...(Params) > 0) { + ctor(result, kj::fwd(params)...); + } + return Own(&result, DestructorOnlyDisposer::instance); +} + +template +Array Arena::allocateOwnArray(size_t size) { + ArrayBuilder result = allocateOwnArrayBuilder(size); + for (size_t i = 0; i < size; i++) { + result.add(); + } + return result.finish(); +} + +template +ArrayBuilder Arena::allocateOwnArrayBuilder(size_t capacity) { + return ArrayBuilder( + reinterpret_cast(allocateBytes(sizeof(T) * capacity, alignof(T), false)), + capacity, DestructorOnlyArrayDisposer::instance); +} + +} // namespace kj + +#endif // KJ_ARENA_H_ diff --git a/phonelibs/capnp-cpp/include/kj/array.h b/phonelibs/capnp-cpp/include/kj/array.h new file mode 100644 index 00000000000000..51b5dcf31949ab --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/array.h @@ -0,0 +1,813 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ARRAY_H_ +#define KJ_ARRAY_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include +#include + +namespace kj { + +// ======================================================================================= +// ArrayDisposer -- Implementation details. + +class ArrayDisposer { + // Much like Disposer from memory.h. + +protected: + // Do not declare a destructor, as doing so will force a global initializer for + // HeapArrayDisposer::instance. + + virtual void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const = 0; + // Disposes of the array. `destroyElement` invokes the destructor of each element, or is nullptr + // if the elements have trivial destructors. `capacity` is the amount of space that was + // allocated while `elementCount` is the number of elements that were actually constructed; + // these are always the same number for Array but may be different when using ArrayBuilder. + +public: + + template + void dispose(T* firstElement, size_t elementCount, size_t capacity) const; + // Helper wrapper around disposeImpl(). + // + // Callers must not call dispose() on the same array twice, even if the first call throws + // an exception. + +private: + template + struct Dispose_; +}; + +class ExceptionSafeArrayUtil { + // Utility class that assists in constructing or destroying elements of an array, where the + // constructor or destructor could throw exceptions. In case of an exception, + // ExceptionSafeArrayUtil's destructor will call destructors on all elements that have been + // constructed but not destroyed. Remember that destructors that throw exceptions are required + // to use UnwindDetector to detect unwind and avoid exceptions in this case. Therefore, no more + // than one exception will be thrown (and the program will not terminate). + +public: + inline ExceptionSafeArrayUtil(void* ptr, size_t elementSize, size_t constructedElementCount, + void (*destroyElement)(void*)) + : pos(reinterpret_cast(ptr) + elementSize * constructedElementCount), + elementSize(elementSize), constructedElementCount(constructedElementCount), + destroyElement(destroyElement) {} + KJ_DISALLOW_COPY(ExceptionSafeArrayUtil); + + inline ~ExceptionSafeArrayUtil() noexcept(false) { + if (constructedElementCount > 0) destroyAll(); + } + + void construct(size_t count, void (*constructElement)(void*)); + // Construct the given number of elements. + + void destroyAll(); + // Destroy all elements. Call this immediately before ExceptionSafeArrayUtil goes out-of-scope + // to ensure that one element throwing an exception does not prevent the others from being + // destroyed. + + void release() { constructedElementCount = 0; } + // Prevent ExceptionSafeArrayUtil's destructor from destroying the constructed elements. + // Call this after you've successfully finished constructing. + +private: + byte* pos; + size_t elementSize; + size_t constructedElementCount; + void (*destroyElement)(void*); +}; + +class DestructorOnlyArrayDisposer: public ArrayDisposer { +public: + static const DestructorOnlyArrayDisposer instance; + + void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const override; +}; + +class NullArrayDisposer: public ArrayDisposer { + // An ArrayDisposer that does nothing. Can be used to construct a fake Arrays that doesn't + // actually own its content. + +public: + static const NullArrayDisposer instance; + + void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const override; +}; + +// ======================================================================================= +// Array + +template +class Array { + // An owned array which will automatically be disposed of (using an ArrayDisposer) in the + // destructor. Can be moved, but not copied. Much like Own, but for arrays rather than + // single objects. + +public: + inline Array(): ptr(nullptr), size_(0), disposer(nullptr) {} + inline Array(decltype(nullptr)): ptr(nullptr), size_(0), disposer(nullptr) {} + inline Array(Array&& other) noexcept + : ptr(other.ptr), size_(other.size_), disposer(other.disposer) { + other.ptr = nullptr; + other.size_ = 0; + } + inline Array(Array>&& other) noexcept + : ptr(other.ptr), size_(other.size_), disposer(other.disposer) { + other.ptr = nullptr; + other.size_ = 0; + } + inline Array(T* firstElement, size_t size, const ArrayDisposer& disposer) + : ptr(firstElement), size_(size), disposer(&disposer) {} + + KJ_DISALLOW_COPY(Array); + inline ~Array() noexcept { dispose(); } + + inline operator ArrayPtr() { + return ArrayPtr(ptr, size_); + } + inline operator ArrayPtr() const { + return ArrayPtr(ptr, size_); + } + inline ArrayPtr asPtr() { + return ArrayPtr(ptr, size_); + } + inline ArrayPtr asPtr() const { + return ArrayPtr(ptr, size_); + } + + inline size_t size() const { return size_; } + inline T& operator[](size_t index) const { + KJ_IREQUIRE(index < size_, "Out-of-bounds Array access."); + return ptr[index]; + } + + inline const T* begin() const { return ptr; } + inline const T* end() const { return ptr + size_; } + inline const T& front() const { return *ptr; } + inline const T& back() const { return *(ptr + size_ - 1); } + inline T* begin() { return ptr; } + inline T* end() { return ptr + size_; } + inline T& front() { return *ptr; } + inline T& back() { return *(ptr + size_ - 1); } + + inline ArrayPtr slice(size_t start, size_t end) { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds Array::slice()."); + return ArrayPtr(ptr + start, end - start); + } + inline ArrayPtr slice(size_t start, size_t end) const { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds Array::slice()."); + return ArrayPtr(ptr + start, end - start); + } + + inline ArrayPtr asBytes() const { return asPtr().asBytes(); } + inline ArrayPtr> asBytes() { return asPtr().asBytes(); } + inline ArrayPtr asChars() const { return asPtr().asChars(); } + inline ArrayPtr> asChars() { return asPtr().asChars(); } + + inline Array> releaseAsBytes() { + // Like asBytes() but transfers ownership. + static_assert(sizeof(T) == sizeof(byte), + "releaseAsBytes() only possible on arrays with byte-size elements (e.g. chars)."); + Array> result( + reinterpret_cast*>(ptr), size_, *disposer); + ptr = nullptr; + size_ = 0; + return result; + } + inline Array> releaseAsChars() { + // Like asChars() but transfers ownership. + static_assert(sizeof(T) == sizeof(PropagateConst), + "releaseAsChars() only possible on arrays with char-size elements (e.g. bytes)."); + Array> result( + reinterpret_cast*>(ptr), size_, *disposer); + ptr = nullptr; + size_ = 0; + return result; + } + + inline bool operator==(decltype(nullptr)) const { return size_ == 0; } + inline bool operator!=(decltype(nullptr)) const { return size_ != 0; } + + inline Array& operator=(decltype(nullptr)) { + dispose(); + return *this; + } + + inline Array& operator=(Array&& other) { + dispose(); + ptr = other.ptr; + size_ = other.size_; + disposer = other.disposer; + other.ptr = nullptr; + other.size_ = 0; + return *this; + } + +private: + T* ptr; + size_t size_; + const ArrayDisposer* disposer; + + inline void dispose() { + // Make sure that if an exception is thrown, we are left with a null ptr, so we won't possibly + // dispose again. + T* ptrCopy = ptr; + size_t sizeCopy = size_; + if (ptrCopy != nullptr) { + ptr = nullptr; + size_ = 0; + disposer->dispose(ptrCopy, sizeCopy, sizeCopy); + } + } + + template + friend class Array; +}; + +static_assert(!canMemcpy>(), "canMemcpy<>() is broken"); + +namespace _ { // private + +class HeapArrayDisposer final: public ArrayDisposer { +public: + template + static T* allocate(size_t count); + template + static T* allocateUninitialized(size_t count); + + static const HeapArrayDisposer instance; + +private: + static void* allocateImpl(size_t elementSize, size_t elementCount, size_t capacity, + void (*constructElement)(void*), void (*destroyElement)(void*)); + // Allocates and constructs the array. Both function pointers are null if the constructor is + // trivial, otherwise destroyElement is null if the constructor doesn't throw. + + virtual void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const override; + + template + struct Allocate_; +}; + +} // namespace _ (private) + +template +inline Array heapArray(size_t size) { + // Much like `heap()` from memory.h, allocates a new array on the heap. + + return Array(_::HeapArrayDisposer::allocate(size), size, + _::HeapArrayDisposer::instance); +} + +template Array heapArray(const T* content, size_t size); +template Array heapArray(ArrayPtr content); +template Array heapArray(ArrayPtr content); +template Array heapArray(Iterator begin, Iterator end); +template Array heapArray(std::initializer_list init); +// Allocate a heap array containing a copy of the given content. + +template +Array heapArrayFromIterable(Container&& a) { return heapArray(a.begin(), a.end()); } +template +Array heapArrayFromIterable(Array&& a) { return mv(a); } + +// ======================================================================================= +// ArrayBuilder + +template +class ArrayBuilder { + // Class which lets you build an Array specifying the exact constructor arguments for each + // element, rather than starting by default-constructing them. + +public: + ArrayBuilder(): ptr(nullptr), pos(nullptr), endPtr(nullptr) {} + ArrayBuilder(decltype(nullptr)): ptr(nullptr), pos(nullptr), endPtr(nullptr) {} + explicit ArrayBuilder(RemoveConst* firstElement, size_t capacity, + const ArrayDisposer& disposer) + : ptr(firstElement), pos(firstElement), endPtr(firstElement + capacity), + disposer(&disposer) {} + ArrayBuilder(ArrayBuilder&& other) + : ptr(other.ptr), pos(other.pos), endPtr(other.endPtr), disposer(other.disposer) { + other.ptr = nullptr; + other.pos = nullptr; + other.endPtr = nullptr; + } + KJ_DISALLOW_COPY(ArrayBuilder); + inline ~ArrayBuilder() noexcept(false) { dispose(); } + + inline operator ArrayPtr() { + return arrayPtr(ptr, pos); + } + inline operator ArrayPtr() const { + return arrayPtr(ptr, pos); + } + inline ArrayPtr asPtr() { + return arrayPtr(ptr, pos); + } + inline ArrayPtr asPtr() const { + return arrayPtr(ptr, pos); + } + + inline size_t size() const { return pos - ptr; } + inline size_t capacity() const { return endPtr - ptr; } + inline T& operator[](size_t index) const { + KJ_IREQUIRE(index < implicitCast(pos - ptr), "Out-of-bounds Array access."); + return ptr[index]; + } + + inline const T* begin() const { return ptr; } + inline const T* end() const { return pos; } + inline const T& front() const { return *ptr; } + inline const T& back() const { return *(pos - 1); } + inline T* begin() { return ptr; } + inline T* end() { return pos; } + inline T& front() { return *ptr; } + inline T& back() { return *(pos - 1); } + + ArrayBuilder& operator=(ArrayBuilder&& other) { + dispose(); + ptr = other.ptr; + pos = other.pos; + endPtr = other.endPtr; + disposer = other.disposer; + other.ptr = nullptr; + other.pos = nullptr; + other.endPtr = nullptr; + return *this; + } + ArrayBuilder& operator=(decltype(nullptr)) { + dispose(); + return *this; + } + + template + T& add(Params&&... params) { + KJ_IREQUIRE(pos < endPtr, "Added too many elements to ArrayBuilder."); + ctor(*pos, kj::fwd(params)...); + return *pos++; + } + + template + void addAll(Container&& container) { + addAll()>( + container.begin(), container.end()); + } + + template + void addAll(Iterator start, Iterator end); + + void removeLast() { + KJ_IREQUIRE(pos > ptr, "No elements present to remove."); + kj::dtor(*--pos); + } + + void truncate(size_t size) { + KJ_IREQUIRE(size <= this->size(), "can't use truncate() to expand"); + + T* target = ptr + size; + if (__has_trivial_destructor(T)) { + pos = target; + } else { + while (pos > target) { + kj::dtor(*--pos); + } + } + } + + void resize(size_t size) { + KJ_IREQUIRE(size <= capacity(), "can't resize past capacity"); + + T* target = ptr + size; + if (target > pos) { + // expand + if (__has_trivial_constructor(T)) { + pos = target; + } else { + while (pos < target) { + kj::ctor(*pos++); + } + } + } else { + // truncate + if (__has_trivial_destructor(T)) { + pos = target; + } else { + while (pos > target) { + kj::dtor(*--pos); + } + } + } + } + + Array finish() { + // We could safely remove this check if we assume that the disposer implementation doesn't + // need to know the original capacity, as is thes case with HeapArrayDisposer since it uses + // operator new() or if we created a custom disposer for ArrayBuilder which stores the capacity + // in a prefix. But that would make it hard to write cleverer heap allocators, and anyway this + // check might catch bugs. Probably people should use Vector if they want to build arrays + // without knowing the final size in advance. + KJ_IREQUIRE(pos == endPtr, "ArrayBuilder::finish() called prematurely."); + Array result(reinterpret_cast(ptr), pos - ptr, *disposer); + ptr = nullptr; + pos = nullptr; + endPtr = nullptr; + return result; + } + + inline bool isFull() const { + return pos == endPtr; + } + +private: + T* ptr; + RemoveConst* pos; + T* endPtr; + const ArrayDisposer* disposer; + + inline void dispose() { + // Make sure that if an exception is thrown, we are left with a null ptr, so we won't possibly + // dispose again. + T* ptrCopy = ptr; + T* posCopy = pos; + T* endCopy = endPtr; + if (ptrCopy != nullptr) { + ptr = nullptr; + pos = nullptr; + endPtr = nullptr; + disposer->dispose(ptrCopy, posCopy - ptrCopy, endCopy - ptrCopy); + } + } +}; + +template +inline ArrayBuilder heapArrayBuilder(size_t size) { + // Like `heapArray()` but does not default-construct the elements. You must construct them + // manually by calling `add()`. + + return ArrayBuilder(_::HeapArrayDisposer::allocateUninitialized>(size), + size, _::HeapArrayDisposer::instance); +} + +// ======================================================================================= +// Inline Arrays + +template +class FixedArray { + // A fixed-width array whose storage is allocated inline rather than on the heap. + +public: + inline size_t size() const { return fixedSize; } + inline T* begin() { return content; } + inline T* end() { return content + fixedSize; } + inline const T* begin() const { return content; } + inline const T* end() const { return content + fixedSize; } + + inline operator ArrayPtr() { + return arrayPtr(content, fixedSize); + } + inline operator ArrayPtr() const { + return arrayPtr(content, fixedSize); + } + + inline T& operator[](size_t index) { return content[index]; } + inline const T& operator[](size_t index) const { return content[index]; } + +private: + T content[fixedSize]; +}; + +template +class CappedArray { + // Like `FixedArray` but can be dynamically resized as long as the size does not exceed the limit + // specified by the template parameter. + // + // TODO(someday): Don't construct elements past currentSize? + +public: + inline KJ_CONSTEXPR() CappedArray(): currentSize(fixedSize) {} + inline explicit constexpr CappedArray(size_t s): currentSize(s) {} + + inline size_t size() const { return currentSize; } + inline void setSize(size_t s) { KJ_IREQUIRE(s <= fixedSize); currentSize = s; } + inline T* begin() { return content; } + inline T* end() { return content + currentSize; } + inline const T* begin() const { return content; } + inline const T* end() const { return content + currentSize; } + + inline operator ArrayPtr() { + return arrayPtr(content, currentSize); + } + inline operator ArrayPtr() const { + return arrayPtr(content, currentSize); + } + + inline T& operator[](size_t index) { return content[index]; } + inline const T& operator[](size_t index) const { return content[index]; } + +private: + size_t currentSize; + T content[fixedSize]; +}; + +// ======================================================================================= +// KJ_MAP + +#define KJ_MAP(elementName, array) \ + ::kj::_::Mapper(array) * \ + [&](typename ::kj::_::Mapper::Element elementName) +// Applies some function to every element of an array, returning an Array of the results, with +// nice syntax. Example: +// +// StringPtr foo = "abcd"; +// Array bar = KJ_MAP(c, foo) -> char { return c + 1; }; +// KJ_ASSERT(str(bar) == "bcde"); + +namespace _ { // private + +template +struct Mapper { + T array; + Mapper(T&& array): array(kj::fwd(array)) {} + template + auto operator*(Func&& func) -> Array { + auto builder = heapArrayBuilder(array.size()); + for (auto iter = array.begin(); iter != array.end(); ++iter) { + builder.add(func(*iter)); + } + return builder.finish(); + } + typedef decltype(*kj::instance().begin()) Element; +}; + +template +struct Mapper { + T* array; + Mapper(T* array): array(array) {} + template + auto operator*(Func&& func) -> Array { + auto builder = heapArrayBuilder(s); + for (size_t i = 0; i < s; i++) { + builder.add(func(array[i])); + } + return builder.finish(); + } + typedef decltype(*array)& Element; +}; + +} // namespace _ (private) + +// ======================================================================================= +// Inline implementation details + +template +struct ArrayDisposer::Dispose_ { + static void dispose(T* firstElement, size_t elementCount, size_t capacity, + const ArrayDisposer& disposer) { + disposer.disposeImpl(const_cast*>(firstElement), + sizeof(T), elementCount, capacity, nullptr); + } +}; +template +struct ArrayDisposer::Dispose_ { + static void destruct(void* ptr) { + kj::dtor(*reinterpret_cast(ptr)); + } + + static void dispose(T* firstElement, size_t elementCount, size_t capacity, + const ArrayDisposer& disposer) { + disposer.disposeImpl(firstElement, sizeof(T), elementCount, capacity, &destruct); + } +}; + +template +void ArrayDisposer::dispose(T* firstElement, size_t elementCount, size_t capacity) const { + Dispose_::dispose(firstElement, elementCount, capacity, *this); +} + +namespace _ { // private + +template +struct HeapArrayDisposer::Allocate_ { + static T* allocate(size_t elementCount, size_t capacity) { + return reinterpret_cast(allocateImpl( + sizeof(T), elementCount, capacity, nullptr, nullptr)); + } +}; +template +struct HeapArrayDisposer::Allocate_ { + static void construct(void* ptr) { + kj::ctor(*reinterpret_cast(ptr)); + } + static T* allocate(size_t elementCount, size_t capacity) { + return reinterpret_cast(allocateImpl( + sizeof(T), elementCount, capacity, &construct, nullptr)); + } +}; +template +struct HeapArrayDisposer::Allocate_ { + static void construct(void* ptr) { + kj::ctor(*reinterpret_cast(ptr)); + } + static void destruct(void* ptr) { + kj::dtor(*reinterpret_cast(ptr)); + } + static T* allocate(size_t elementCount, size_t capacity) { + return reinterpret_cast(allocateImpl( + sizeof(T), elementCount, capacity, &construct, &destruct)); + } +}; + +template +T* HeapArrayDisposer::allocate(size_t count) { + return Allocate_::allocate(count, count); +} + +template +T* HeapArrayDisposer::allocateUninitialized(size_t count) { + return Allocate_::allocate(0, count); +} + +template ()> +struct CopyConstructArray_; + +template +struct CopyConstructArray_ { + static inline T* apply(T* __restrict__ pos, T* start, T* end) { + memcpy(pos, start, reinterpret_cast(end) - reinterpret_cast(start)); + return pos + (end - start); + } +}; + +template +struct CopyConstructArray_ { + static inline T* apply(T* __restrict__ pos, const T* start, const T* end) { + memcpy(pos, start, reinterpret_cast(end) - reinterpret_cast(start)); + return pos + (end - start); + } +}; + +template +struct CopyConstructArray_ { + static inline T* apply(T* __restrict__ pos, Iterator start, Iterator end) { + // Since both the copy constructor and assignment operator are trivial, we know that assignment + // is equivalent to copy-constructing. So we can make this case somewhat easier for the + // compiler to optimize. + while (start != end) { + *pos++ = *start++; + } + return pos; + } +}; + +template +struct CopyConstructArray_ { + struct ExceptionGuard { + T* start; + T* pos; + inline explicit ExceptionGuard(T* pos): start(pos), pos(pos) {} + ~ExceptionGuard() noexcept(false) { + while (pos > start) { + dtor(*--pos); + } + } + }; + + static T* apply(T* __restrict__ pos, Iterator start, Iterator end) { + // Verify that T can be *implicitly* constructed from the source values. + if (false) implicitCast(*start); + + if (noexcept(T(*start))) { + while (start != end) { + ctor(*pos++, *start++); + } + return pos; + } else { + // Crap. This is complicated. + ExceptionGuard guard(pos); + while (start != end) { + ctor(*guard.pos, *start++); + ++guard.pos; + } + guard.start = guard.pos; + return guard.pos; + } + } +}; + +template +struct CopyConstructArray_ { + // Actually move-construct. + + struct ExceptionGuard { + T* start; + T* pos; + inline explicit ExceptionGuard(T* pos): start(pos), pos(pos) {} + ~ExceptionGuard() noexcept(false) { + while (pos > start) { + dtor(*--pos); + } + } + }; + + static T* apply(T* __restrict__ pos, Iterator start, Iterator end) { + // Verify that T can be *implicitly* constructed from the source values. + if (false) implicitCast(kj::mv(*start)); + + if (noexcept(T(kj::mv(*start)))) { + while (start != end) { + ctor(*pos++, kj::mv(*start++)); + } + return pos; + } else { + // Crap. This is complicated. + ExceptionGuard guard(pos); + while (start != end) { + ctor(*guard.pos, kj::mv(*start++)); + ++guard.pos; + } + guard.start = guard.pos; + return guard.pos; + } + } +}; + +} // namespace _ (private) + +template +template +void ArrayBuilder::addAll(Iterator start, Iterator end) { + pos = _::CopyConstructArray_, Decay, move>::apply(pos, start, end); +} + +template +Array heapArray(const T* content, size_t size) { + ArrayBuilder builder = heapArrayBuilder(size); + builder.addAll(content, content + size); + return builder.finish(); +} + +template +Array heapArray(T* content, size_t size) { + ArrayBuilder builder = heapArrayBuilder(size); + builder.addAll(content, content + size); + return builder.finish(); +} + +template +Array heapArray(ArrayPtr content) { + ArrayBuilder builder = heapArrayBuilder(content.size()); + builder.addAll(content); + return builder.finish(); +} + +template +Array heapArray(ArrayPtr content) { + ArrayBuilder builder = heapArrayBuilder(content.size()); + builder.addAll(content); + return builder.finish(); +} + +template Array +heapArray(Iterator begin, Iterator end) { + ArrayBuilder builder = heapArrayBuilder(end - begin); + builder.addAll(begin, end); + return builder.finish(); +} + +template +inline Array heapArray(std::initializer_list init) { + return heapArray(init.begin(), init.end()); +} + +} // namespace kj + +#endif // KJ_ARRAY_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-inl.h b/phonelibs/capnp-cpp/include/kj/async-inl.h new file mode 100644 index 00000000000000..f11e4fcd5b9f74 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-inl.h @@ -0,0 +1,1112 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains extended inline implementation details that are required along with async.h. +// We move this all into a separate file to make async.h more readable. +// +// Non-inline declarations here are defined in async.c++. + +#ifndef KJ_ASYNC_H_ +#error "Do not include this directly; include kj/async.h." +#include "async.h" // help IDE parse this file +#endif + +#ifndef KJ_ASYNC_INL_H_ +#define KJ_ASYNC_INL_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +namespace kj { +namespace _ { // private + +template +class ExceptionOr; + +class ExceptionOrValue { +public: + ExceptionOrValue(bool, Exception&& exception): exception(kj::mv(exception)) {} + KJ_DISALLOW_COPY(ExceptionOrValue); + + void addException(Exception&& exception) { + if (this->exception == nullptr) { + this->exception = kj::mv(exception); + } + } + + template + ExceptionOr& as() { return *static_cast*>(this); } + template + const ExceptionOr& as() const { return *static_cast*>(this); } + + Maybe exception; + +protected: + // Allow subclasses to have move constructor / assignment. + ExceptionOrValue() = default; + ExceptionOrValue(ExceptionOrValue&& other) = default; + ExceptionOrValue& operator=(ExceptionOrValue&& other) = default; +}; + +template +class ExceptionOr: public ExceptionOrValue { +public: + ExceptionOr() = default; + ExceptionOr(T&& value): value(kj::mv(value)) {} + ExceptionOr(bool, Exception&& exception): ExceptionOrValue(false, kj::mv(exception)) {} + ExceptionOr(ExceptionOr&&) = default; + ExceptionOr& operator=(ExceptionOr&&) = default; + + Maybe value; +}; + +class Event { + // An event waiting to be executed. Not for direct use by applications -- promises use this + // internally. + +public: + Event(); + ~Event() noexcept(false); + KJ_DISALLOW_COPY(Event); + + void armDepthFirst(); + // Enqueue this event so that `fire()` will be called from the event loop soon. + // + // Events scheduled in this way are executed in depth-first order: if an event callback arms + // more events, those events are placed at the front of the queue (in the order in which they + // were armed), so that they run immediately after the first event's callback returns. + // + // Depth-first event scheduling is appropriate for events that represent simple continuations + // of a previous event that should be globbed together for performance. Depth-first scheduling + // can lead to starvation, so any long-running task must occasionally yield with + // `armBreadthFirst()`. (Promise::then() uses depth-first whereas evalLater() uses + // breadth-first.) + // + // To use breadth-first scheduling instead, use `armBreadthFirst()`. + + void armBreadthFirst(); + // Like `armDepthFirst()` except that the event is placed at the end of the queue. + + kj::String trace(); + // Dump debug info about this event. + + virtual _::PromiseNode* getInnerForTrace(); + // If this event wraps a PromiseNode, get that node. Used for debug tracing. + // Default implementation returns nullptr. + +protected: + virtual Maybe> fire() = 0; + // Fire the event. Possibly returns a pointer to itself, which will be discarded by the + // caller. This is the only way that an event can delete itself as a result of firing, as + // doing so from within fire() will throw an exception. + +private: + friend class kj::EventLoop; + EventLoop& loop; + Event* next; + Event** prev; + bool firing = false; +}; + +class PromiseNode { + // A Promise contains a chain of PromiseNodes tracking the pending transformations. + // + // To reduce generated code bloat, PromiseNode is not a template. Instead, it makes very hacky + // use of pointers to ExceptionOrValue which actually point to ExceptionOr, but are only + // so down-cast in the few places that really need to be templated. Luckily this is all + // internal implementation details. + +public: + virtual void onReady(Event& event) noexcept = 0; + // Arms the given event when ready. + + virtual void setSelfPointer(Own* selfPtr) noexcept; + // Tells the node that `selfPtr` is the pointer that owns this node, and will continue to own + // this node until it is destroyed or setSelfPointer() is called again. ChainPromiseNode uses + // this to shorten redundant chains. The default implementation does nothing; only + // ChainPromiseNode should implement this. + + virtual void get(ExceptionOrValue& output) noexcept = 0; + // Get the result. `output` points to an ExceptionOr into which the result will be written. + // Can only be called once, and only after the node is ready. Must be called directly from the + // event loop, with no application code on the stack. + + virtual PromiseNode* getInnerForTrace(); + // If this node wraps some other PromiseNode, get the wrapped node. Used for debug tracing. + // Default implementation returns nullptr. + +protected: + class OnReadyEvent { + // Helper class for implementing onReady(). + + public: + void init(Event& newEvent); + // Returns true if arm() was already called. + + void arm(); + // Arms the event if init() has already been called and makes future calls to init() return + // true. + + private: + Event* event = nullptr; + }; +}; + +// ------------------------------------------------------------------- + +class ImmediatePromiseNodeBase: public PromiseNode { +public: + ImmediatePromiseNodeBase(); + ~ImmediatePromiseNodeBase() noexcept(false); + + void onReady(Event& event) noexcept override; +}; + +template +class ImmediatePromiseNode final: public ImmediatePromiseNodeBase { + // A promise that has already been resolved to an immediate value or exception. + +public: + ImmediatePromiseNode(ExceptionOr&& result): result(kj::mv(result)) {} + + void get(ExceptionOrValue& output) noexcept override { + output.as() = kj::mv(result); + } + +private: + ExceptionOr result; +}; + +class ImmediateBrokenPromiseNode final: public ImmediatePromiseNodeBase { +public: + ImmediateBrokenPromiseNode(Exception&& exception); + + void get(ExceptionOrValue& output) noexcept override; + +private: + Exception exception; +}; + +// ------------------------------------------------------------------- + +class AttachmentPromiseNodeBase: public PromiseNode { +public: + AttachmentPromiseNodeBase(Own&& dependency); + + void onReady(Event& event) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + Own dependency; + + void dropDependency(); + + template + friend class AttachmentPromiseNode; +}; + +template +class AttachmentPromiseNode final: public AttachmentPromiseNodeBase { + // A PromiseNode that holds on to some object (usually, an Own, but could be any movable + // object) until the promise resolves. + +public: + AttachmentPromiseNode(Own&& dependency, Attachment&& attachment) + : AttachmentPromiseNodeBase(kj::mv(dependency)), + attachment(kj::mv(attachment)) {} + + ~AttachmentPromiseNode() noexcept(false) { + // We need to make sure the dependency is deleted before we delete the attachment because the + // dependency may be using the attachment. + dropDependency(); + } + +private: + Attachment attachment; +}; + +// ------------------------------------------------------------------- + +class PtmfHelper { + // This class is a private helper for GetFunctorStartAddress. The class represents the internal + // representation of a pointer-to-member-function. + + template + friend struct GetFunctorStartAddress; + +#if __GNUG__ + + void* ptr; + ptrdiff_t adj; + // Layout of a pointer-to-member-function used by GCC and compatible compilers. + + void* apply(void* obj) { +#if defined(__arm__) || defined(__mips__) || defined(__aarch64__) + if (adj & 1) { + ptrdiff_t voff = (ptrdiff_t)ptr; +#else + ptrdiff_t voff = (ptrdiff_t)ptr; + if (voff & 1) { + voff &= ~1; +#endif + return *(void**)(*(char**)obj + voff); + } else { + return ptr; + } + } + +#define BODY \ + PtmfHelper result; \ + static_assert(sizeof(p) == sizeof(result), "unknown ptmf layout"); \ + memcpy(&result, &p, sizeof(result)); \ + return result + +#else // __GNUG__ + + void* apply(void* obj) { return nullptr; } + // TODO(port): PTMF instruction address extraction + +#define BODY return PtmfHelper{} + +#endif // __GNUG__, else + + template + static PtmfHelper from(F p) { BODY; } + // Create a PtmfHelper from some arbitrary pointer-to-member-function which is not + // overloaded nor a template. In this case the compiler is able to deduce the full function + // signature directly given the name since there is only one function with that name. + + template + static PtmfHelper from(R (C::*p)(NoInfer

...)) { BODY; } + template + static PtmfHelper from(R (C::*p)(NoInfer

...) const) { BODY; } + // Create a PtmfHelper from some poniter-to-member-function which is a template. In this case + // the function must match exactly the containing type C, return type R, and parameter types P... + // GetFunctorStartAddress normally specifies exactly the correct C and R, but can only make a + // guess at P. Luckily, if the function parameters are template parameters then it's not + // necessary to be precise about P. +#undef BODY +}; + +template +struct GetFunctorStartAddress { + // Given a functor (any object defining operator()), return the start address of the function, + // suitable for passing to addr2line to obtain a source file/line for debugging purposes. + // + // This turns out to be incredibly hard to implement in the presence of overloaded or templated + // functors. Therefore, we impose these specific restrictions, specific to our use case: + // - Overloading is not allowed, but templating is. (Generally we only intend to support lambdas + // anyway.) + // - The template parameters to GetFunctorStartAddress specify a hint as to the expected + // parameter types. If the functor is templated, its parameters must match exactly these types. + // (If it's not templated, ParamTypes are ignored.) + + template + static void* apply(Func&& func) { + typedef decltype(func(instance()...)) ReturnType; + return PtmfHelper::from, ParamTypes...>( + &Decay::operator()).apply(&func); + } +}; + +template <> +struct GetFunctorStartAddress: public GetFunctorStartAddress<> {}; +// Hack for TransformPromiseNode use case: an input type of `Void` indicates that the function +// actually has no parameters. + +class TransformPromiseNodeBase: public PromiseNode { +public: + TransformPromiseNodeBase(Own&& dependency, void* continuationTracePtr); + + void onReady(Event& event) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + Own dependency; + void* continuationTracePtr; + + void dropDependency(); + void getDepResult(ExceptionOrValue& output); + + virtual void getImpl(ExceptionOrValue& output) = 0; + + template + friend class TransformPromiseNode; +}; + +template +class TransformPromiseNode final: public TransformPromiseNodeBase { + // A PromiseNode that transforms the result of another PromiseNode through an application-provided + // function (implements `then()`). + +public: + TransformPromiseNode(Own&& dependency, Func&& func, ErrorFunc&& errorHandler) + : TransformPromiseNodeBase(kj::mv(dependency), + GetFunctorStartAddress::apply(func)), + func(kj::fwd(func)), errorHandler(kj::fwd(errorHandler)) {} + + ~TransformPromiseNode() noexcept(false) { + // We need to make sure the dependency is deleted before we delete the continuations because it + // is a common pattern for the continuations to hold ownership of objects that might be in-use + // by the dependency. + dropDependency(); + } + +private: + Func func; + ErrorFunc errorHandler; + + void getImpl(ExceptionOrValue& output) override { + ExceptionOr depResult; + getDepResult(depResult); + KJ_IF_MAYBE(depException, depResult.exception) { + output.as() = handle( + MaybeVoidCaller>>::apply( + errorHandler, kj::mv(*depException))); + } else KJ_IF_MAYBE(depValue, depResult.value) { + output.as() = handle(MaybeVoidCaller::apply(func, kj::mv(*depValue))); + } + } + + ExceptionOr handle(T&& value) { + return kj::mv(value); + } + ExceptionOr handle(PropagateException::Bottom&& value) { + return ExceptionOr(false, value.asException()); + } +}; + +// ------------------------------------------------------------------- + +class ForkHubBase; + +class ForkBranchBase: public PromiseNode { +public: + ForkBranchBase(Own&& hub); + ~ForkBranchBase() noexcept(false); + + void hubReady() noexcept; + // Called by the hub to indicate that it is ready. + + // implements PromiseNode ------------------------------------------ + void onReady(Event& event) noexcept override; + PromiseNode* getInnerForTrace() override; + +protected: + inline ExceptionOrValue& getHubResultRef(); + + void releaseHub(ExceptionOrValue& output); + // Release the hub. If an exception is thrown, add it to `output`. + +private: + OnReadyEvent onReadyEvent; + + Own hub; + ForkBranchBase* next = nullptr; + ForkBranchBase** prevPtr = nullptr; + + friend class ForkHubBase; +}; + +template T copyOrAddRef(T& t) { return t; } +template Own copyOrAddRef(Own& t) { return t->addRef(); } + +template +class ForkBranch final: public ForkBranchBase { + // A PromiseNode that implements one branch of a fork -- i.e. one of the branches that receives + // a const reference. + +public: + ForkBranch(Own&& hub): ForkBranchBase(kj::mv(hub)) {} + + void get(ExceptionOrValue& output) noexcept override { + ExceptionOr& hubResult = getHubResultRef().template as(); + KJ_IF_MAYBE(value, hubResult.value) { + output.as().value = copyOrAddRef(*value); + } else { + output.as().value = nullptr; + } + output.exception = hubResult.exception; + releaseHub(output); + } +}; + +template +class SplitBranch final: public ForkBranchBase { + // A PromiseNode that implements one branch of a fork -- i.e. one of the branches that receives + // a const reference. + +public: + SplitBranch(Own&& hub): ForkBranchBase(kj::mv(hub)) {} + + typedef kj::Decay(kj::instance()))> Element; + + void get(ExceptionOrValue& output) noexcept override { + ExceptionOr& hubResult = getHubResultRef().template as(); + KJ_IF_MAYBE(value, hubResult.value) { + output.as().value = kj::mv(kj::get(*value)); + } else { + output.as().value = nullptr; + } + output.exception = hubResult.exception; + releaseHub(output); + } +}; + +// ------------------------------------------------------------------- + +class ForkHubBase: public Refcounted, protected Event { +public: + ForkHubBase(Own&& inner, ExceptionOrValue& resultRef); + + inline ExceptionOrValue& getResultRef() { return resultRef; } + +private: + Own inner; + ExceptionOrValue& resultRef; + + ForkBranchBase* headBranch = nullptr; + ForkBranchBase** tailBranch = &headBranch; + // Tail becomes null once the inner promise is ready and all branches have been notified. + + Maybe> fire() override; + _::PromiseNode* getInnerForTrace() override; + + friend class ForkBranchBase; +}; + +template +class ForkHub final: public ForkHubBase { + // A PromiseNode that implements the hub of a fork. The first call to Promise::fork() replaces + // the promise's outer node with a ForkHub, and subsequent calls add branches to that hub (if + // possible). + +public: + ForkHub(Own&& inner): ForkHubBase(kj::mv(inner), result) {} + + Promise<_::UnfixVoid> addBranch() { + return Promise<_::UnfixVoid>(false, kj::heap>(addRef(*this))); + } + + _::SplitTuplePromise split() { + return splitImpl(MakeIndexes()>()); + } + +private: + ExceptionOr result; + + template + _::SplitTuplePromise splitImpl(Indexes) { + return kj::tuple(addSplit()...); + } + + template + Promise::Element>> addSplit() { + return Promise::Element>>( + false, maybeChain(kj::heap>(addRef(*this)), + implicitCast::Element*>(nullptr))); + } +}; + +inline ExceptionOrValue& ForkBranchBase::getHubResultRef() { + return hub->getResultRef(); +} + +// ------------------------------------------------------------------- + +class ChainPromiseNode final: public PromiseNode, public Event { + // Promise node which reduces Promise> to Promise. + // + // `Event` is only a public base class because otherwise we can't cast Own to + // Own. Ugh, templates and private... + +public: + explicit ChainPromiseNode(Own inner); + ~ChainPromiseNode() noexcept(false); + + void onReady(Event& event) noexcept override; + void setSelfPointer(Own* selfPtr) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + enum State { + STEP1, + STEP2 + }; + + State state; + + Own inner; + // In STEP1, a PromiseNode for a Promise. + // In STEP2, a PromiseNode for a T. + + Event* onReadyEvent = nullptr; + Own* selfPtr = nullptr; + + Maybe> fire() override; +}; + +template +Own maybeChain(Own&& node, Promise*) { + return heap(kj::mv(node)); +} + +template +Own&& maybeChain(Own&& node, T*) { + return kj::mv(node); +} + +// ------------------------------------------------------------------- + +class ExclusiveJoinPromiseNode final: public PromiseNode { +public: + ExclusiveJoinPromiseNode(Own left, Own right); + ~ExclusiveJoinPromiseNode() noexcept(false); + + void onReady(Event& event) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + class Branch: public Event { + public: + Branch(ExclusiveJoinPromiseNode& joinNode, Own dependency); + ~Branch() noexcept(false); + + bool get(ExceptionOrValue& output); + // Returns true if this is the side that finished. + + Maybe> fire() override; + _::PromiseNode* getInnerForTrace() override; + + private: + ExclusiveJoinPromiseNode& joinNode; + Own dependency; + }; + + Branch left; + Branch right; + OnReadyEvent onReadyEvent; +}; + +// ------------------------------------------------------------------- + +class ArrayJoinPromiseNodeBase: public PromiseNode { +public: + ArrayJoinPromiseNodeBase(Array> promises, + ExceptionOrValue* resultParts, size_t partSize); + ~ArrayJoinPromiseNodeBase() noexcept(false); + + void onReady(Event& event) noexcept override final; + void get(ExceptionOrValue& output) noexcept override final; + PromiseNode* getInnerForTrace() override final; + +protected: + virtual void getNoError(ExceptionOrValue& output) noexcept = 0; + // Called to compile the result only in the case where there were no errors. + +private: + uint countLeft; + OnReadyEvent onReadyEvent; + + class Branch final: public Event { + public: + Branch(ArrayJoinPromiseNodeBase& joinNode, Own dependency, + ExceptionOrValue& output); + ~Branch() noexcept(false); + + Maybe> fire() override; + _::PromiseNode* getInnerForTrace() override; + + Maybe getPart(); + // Calls dependency->get(output). If there was an exception, return it. + + private: + ArrayJoinPromiseNodeBase& joinNode; + Own dependency; + ExceptionOrValue& output; + }; + + Array branches; +}; + +template +class ArrayJoinPromiseNode final: public ArrayJoinPromiseNodeBase { +public: + ArrayJoinPromiseNode(Array> promises, + Array> resultParts) + : ArrayJoinPromiseNodeBase(kj::mv(promises), resultParts.begin(), sizeof(ExceptionOr)), + resultParts(kj::mv(resultParts)) {} + +protected: + void getNoError(ExceptionOrValue& output) noexcept override { + auto builder = heapArrayBuilder(resultParts.size()); + for (auto& part: resultParts) { + KJ_IASSERT(part.value != nullptr, + "Bug in KJ promise framework: Promise result had neither value no exception."); + builder.add(kj::mv(*_::readMaybe(part.value))); + } + output.as>() = builder.finish(); + } + +private: + Array> resultParts; +}; + +template <> +class ArrayJoinPromiseNode final: public ArrayJoinPromiseNodeBase { +public: + ArrayJoinPromiseNode(Array> promises, + Array> resultParts); + ~ArrayJoinPromiseNode(); + +protected: + void getNoError(ExceptionOrValue& output) noexcept override; + +private: + Array> resultParts; +}; + +// ------------------------------------------------------------------- + +class EagerPromiseNodeBase: public PromiseNode, protected Event { + // A PromiseNode that eagerly evaluates its dependency even if its dependent does not eagerly + // evaluate it. + +public: + EagerPromiseNodeBase(Own&& dependency, ExceptionOrValue& resultRef); + + void onReady(Event& event) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + Own dependency; + OnReadyEvent onReadyEvent; + + ExceptionOrValue& resultRef; + + Maybe> fire() override; +}; + +template +class EagerPromiseNode final: public EagerPromiseNodeBase { +public: + EagerPromiseNode(Own&& dependency) + : EagerPromiseNodeBase(kj::mv(dependency), result) {} + + void get(ExceptionOrValue& output) noexcept override { + output.as() = kj::mv(result); + } + +private: + ExceptionOr result; +}; + +template +Own spark(Own&& node) { + // Forces evaluation of the given node to begin as soon as possible, even if no one is waiting + // on it. + return heap>(kj::mv(node)); +} + +// ------------------------------------------------------------------- + +class AdapterPromiseNodeBase: public PromiseNode { +public: + void onReady(Event& event) noexcept override; + +protected: + inline void setReady() { + onReadyEvent.arm(); + } + +private: + OnReadyEvent onReadyEvent; +}; + +template +class AdapterPromiseNode final: public AdapterPromiseNodeBase, + private PromiseFulfiller> { + // A PromiseNode that wraps a PromiseAdapter. + +public: + template + AdapterPromiseNode(Params&&... params) + : adapter(static_cast>&>(*this), kj::fwd(params)...) {} + + void get(ExceptionOrValue& output) noexcept override { + KJ_IREQUIRE(!isWaiting()); + output.as() = kj::mv(result); + } + +private: + ExceptionOr result; + bool waiting = true; + Adapter adapter; + + void fulfill(T&& value) override { + if (waiting) { + waiting = false; + result = ExceptionOr(kj::mv(value)); + setReady(); + } + } + + void reject(Exception&& exception) override { + if (waiting) { + waiting = false; + result = ExceptionOr(false, kj::mv(exception)); + setReady(); + } + } + + bool isWaiting() override { + return waiting; + } +}; + +} // namespace _ (private) + +// ======================================================================================= + +template +Promise::Promise(_::FixVoid value) + : PromiseBase(heap<_::ImmediatePromiseNode<_::FixVoid>>(kj::mv(value))) {} + +template +Promise::Promise(kj::Exception&& exception) + : PromiseBase(heap<_::ImmediateBrokenPromiseNode>(kj::mv(exception))) {} + +template +template +PromiseForResult Promise::then(Func&& func, ErrorFunc&& errorHandler) { + typedef _::FixVoid<_::ReturnType> ResultT; + + Own<_::PromiseNode> intermediate = + heap<_::TransformPromiseNode, Func, ErrorFunc>>( + kj::mv(node), kj::fwd(func), kj::fwd(errorHandler)); + return PromiseForResult(false, + _::maybeChain(kj::mv(intermediate), implicitCast(nullptr))); +} + +namespace _ { // private + +template +struct IdentityFunc { + inline T operator()(T&& value) const { + return kj::mv(value); + } +}; +template +struct IdentityFunc> { + inline Promise operator()(T&& value) const { + return kj::mv(value); + } +}; +template <> +struct IdentityFunc { + inline void operator()() const {} +}; +template <> +struct IdentityFunc> { + Promise operator()() const; + // This can't be inline because it will make the translation unit depend on kj-async. Awkwardly, + // Cap'n Proto relies on being able to include this header without creating such a link-time + // dependency. +}; + +} // namespace _ (private) + +template +template +Promise Promise::catch_(ErrorFunc&& errorHandler) { + // then()'s ErrorFunc can only return a Promise if Func also returns a Promise. In this case, + // Func is being filled in automatically. We want to make sure ErrorFunc can return a Promise, + // but we don't want the extra overhead of promise chaining if ErrorFunc doesn't actually + // return a promise. So we make our Func return match ErrorFunc. + return then(_::IdentityFunc()))>(), + kj::fwd(errorHandler)); +} + +template +T Promise::wait(WaitScope& waitScope) { + _::ExceptionOr<_::FixVoid> result; + + waitImpl(kj::mv(node), result, waitScope); + + KJ_IF_MAYBE(value, result.value) { + KJ_IF_MAYBE(exception, result.exception) { + throwRecoverableException(kj::mv(*exception)); + } + return _::returnMaybeVoid(kj::mv(*value)); + } else KJ_IF_MAYBE(exception, result.exception) { + throwFatalException(kj::mv(*exception)); + } else { + // Result contained neither a value nor an exception? + KJ_UNREACHABLE; + } +} + +template <> +inline void Promise::wait(WaitScope& waitScope) { + // Override case to use throwRecoverableException(). + + _::ExceptionOr<_::Void> result; + + waitImpl(kj::mv(node), result, waitScope); + + if (result.value != nullptr) { + KJ_IF_MAYBE(exception, result.exception) { + throwRecoverableException(kj::mv(*exception)); + } + } else KJ_IF_MAYBE(exception, result.exception) { + throwRecoverableException(kj::mv(*exception)); + } else { + // Result contained neither a value nor an exception? + KJ_UNREACHABLE; + } +} + +template +ForkedPromise Promise::fork() { + return ForkedPromise(false, refcounted<_::ForkHub<_::FixVoid>>(kj::mv(node))); +} + +template +Promise ForkedPromise::addBranch() { + return hub->addBranch(); +} + +template +_::SplitTuplePromise Promise::split() { + return refcounted<_::ForkHub<_::FixVoid>>(kj::mv(node))->split(); +} + +template +Promise Promise::exclusiveJoin(Promise&& other) { + return Promise(false, heap<_::ExclusiveJoinPromiseNode>(kj::mv(node), kj::mv(other.node))); +} + +template +template +Promise Promise::attach(Attachments&&... attachments) { + return Promise(false, kj::heap<_::AttachmentPromiseNode>>( + kj::mv(node), kj::tuple(kj::fwd(attachments)...))); +} + +template +template +Promise Promise::eagerlyEvaluate(ErrorFunc&& errorHandler) { + // See catch_() for commentary. + return Promise(false, _::spark<_::FixVoid>(then( + _::IdentityFunc()))>(), + kj::fwd(errorHandler)).node)); +} + +template +Promise Promise::eagerlyEvaluate(decltype(nullptr)) { + return Promise(false, _::spark<_::FixVoid>(kj::mv(node))); +} + +template +kj::String Promise::trace() { + return PromiseBase::trace(); +} + +template +inline PromiseForResult evalLater(Func&& func) { + return _::yield().then(kj::fwd(func), _::PropagateException()); +} + +template +inline PromiseForResult evalNow(Func&& func) { + PromiseForResult result = nullptr; + KJ_IF_MAYBE(e, kj::runCatchingExceptions([&]() { + result = func(); + })) { + result = kj::mv(*e); + } + return result; +} + +template +template +void Promise::detach(ErrorFunc&& errorHandler) { + return _::detach(then([](T&&) {}, kj::fwd(errorHandler))); +} + +template <> +template +void Promise::detach(ErrorFunc&& errorHandler) { + return _::detach(then([]() {}, kj::fwd(errorHandler))); +} + +template +Promise> joinPromises(Array>&& promises) { + return Promise>(false, kj::heap<_::ArrayJoinPromiseNode>( + KJ_MAP(p, promises) { return kj::mv(p.node); }, + heapArray<_::ExceptionOr>(promises.size()))); +} + +// ======================================================================================= + +namespace _ { // private + +template +class WeakFulfiller final: public PromiseFulfiller, private kj::Disposer { + // A wrapper around PromiseFulfiller which can be detached. + // + // There are a couple non-trivialities here: + // - If the WeakFulfiller is discarded, we want the promise it fulfills to be implicitly + // rejected. + // - We cannot destroy the WeakFulfiller until the application has discarded it *and* it has been + // detached from the underlying fulfiller, because otherwise the later detach() call will go + // to a dangling pointer. Essentially, WeakFulfiller is reference counted, although the + // refcount never goes over 2 and we manually implement the refcounting because we need to do + // other special things when each side detaches anyway. To this end, WeakFulfiller is its own + // Disposer -- dispose() is called when the application discards its owned pointer to the + // fulfiller and detach() is called when the promise is destroyed. + +public: + KJ_DISALLOW_COPY(WeakFulfiller); + + static kj::Own make() { + WeakFulfiller* ptr = new WeakFulfiller; + return Own(ptr, *ptr); + } + + void fulfill(FixVoid&& value) override { + if (inner != nullptr) { + inner->fulfill(kj::mv(value)); + } + } + + void reject(Exception&& exception) override { + if (inner != nullptr) { + inner->reject(kj::mv(exception)); + } + } + + bool isWaiting() override { + return inner != nullptr && inner->isWaiting(); + } + + void attach(PromiseFulfiller& newInner) { + inner = &newInner; + } + + void detach(PromiseFulfiller& from) { + if (inner == nullptr) { + // Already disposed. + delete this; + } else { + KJ_IREQUIRE(inner == &from); + inner = nullptr; + } + } + +private: + mutable PromiseFulfiller* inner; + + WeakFulfiller(): inner(nullptr) {} + + void disposeImpl(void* pointer) const override { + // TODO(perf): Factor some of this out so it isn't regenerated for every fulfiller type? + + if (inner == nullptr) { + // Already detached. + delete this; + } else { + if (inner->isWaiting()) { + inner->reject(kj::Exception(kj::Exception::Type::FAILED, __FILE__, __LINE__, + kj::heapString("PromiseFulfiller was destroyed without fulfilling the promise."))); + } + inner = nullptr; + } + } +}; + +template +class PromiseAndFulfillerAdapter { +public: + PromiseAndFulfillerAdapter(PromiseFulfiller& fulfiller, + WeakFulfiller& wrapper) + : fulfiller(fulfiller), wrapper(wrapper) { + wrapper.attach(fulfiller); + } + + ~PromiseAndFulfillerAdapter() noexcept(false) { + wrapper.detach(fulfiller); + } + +private: + PromiseFulfiller& fulfiller; + WeakFulfiller& wrapper; +}; + +} // namespace _ (private) + +template +template +bool PromiseFulfiller::rejectIfThrows(Func&& func) { + KJ_IF_MAYBE(exception, kj::runCatchingExceptions(kj::mv(func))) { + reject(kj::mv(*exception)); + return false; + } else { + return true; + } +} + +template +bool PromiseFulfiller::rejectIfThrows(Func&& func) { + KJ_IF_MAYBE(exception, kj::runCatchingExceptions(kj::mv(func))) { + reject(kj::mv(*exception)); + return false; + } else { + return true; + } +} + +template +Promise newAdaptedPromise(Params&&... adapterConstructorParams) { + return Promise(false, heap<_::AdapterPromiseNode<_::FixVoid, Adapter>>( + kj::fwd(adapterConstructorParams)...)); +} + +template +PromiseFulfillerPair newPromiseAndFulfiller() { + auto wrapper = _::WeakFulfiller::make(); + + Own<_::PromiseNode> intermediate( + heap<_::AdapterPromiseNode<_::FixVoid, _::PromiseAndFulfillerAdapter>>(*wrapper)); + Promise<_::JoinPromises> promise(false, + _::maybeChain(kj::mv(intermediate), implicitCast(nullptr))); + + return PromiseFulfillerPair { kj::mv(promise), kj::mv(wrapper) }; +} + +} // namespace kj + +#endif // KJ_ASYNC_INL_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-io.h b/phonelibs/capnp-cpp/include/kj/async-io.h new file mode 100644 index 00000000000000..2804ed7289603d --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-io.h @@ -0,0 +1,561 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_IO_H_ +#define KJ_ASYNC_IO_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async.h" +#include "function.h" +#include "thread.h" +#include "time.h" + +struct sockaddr; + +namespace kj { + +#if _WIN32 +class Win32EventPort; +#else +class UnixEventPort; +#endif + +class NetworkAddress; +class AsyncOutputStream; + +// ======================================================================================= +// Streaming I/O + +class AsyncInputStream { + // Asynchronous equivalent of InputStream (from io.h). + +public: + virtual Promise read(void* buffer, size_t minBytes, size_t maxBytes); + virtual Promise tryRead(void* buffer, size_t minBytes, size_t maxBytes) = 0; + + Promise read(void* buffer, size_t bytes); + + virtual Maybe tryGetLength(); + // Get the remaining number of bytes that will be produced by this stream, if known. + // + // This is used e.g. to fill in the Content-Length header of an HTTP message. If unknown, the + // HTTP implementation may need to fall back to Transfer-Encoding: chunked. + // + // The default implementation always returns null. + + virtual Promise pumpTo( + AsyncOutputStream& output, uint64_t amount = kj::maxValue); + // Read `amount` bytes from this stream (or to EOF) and write them to `output`, returning the + // total bytes actually pumped (which is only less than `amount` if EOF was reached). + // + // Override this if your stream type knows how to pump itself to certain kinds of output + // streams more efficiently than via the naive approach. You can use + // kj::dynamicDowncastIfAvailable() to test for stream types you recognize, and if none match, + // delegate to the default implementation. + // + // The default implementation first tries calling output.tryPumpFrom(), but if that fails, it + // performs a naive pump by allocating a buffer and reading to it / writing from it in a loop. + + Promise> readAllBytes(); + Promise readAllText(); + // Read until EOF and return as one big byte array or string. +}; + +class AsyncOutputStream { + // Asynchronous equivalent of OutputStream (from io.h). + +public: + virtual Promise write(const void* buffer, size_t size) KJ_WARN_UNUSED_RESULT = 0; + virtual Promise write(ArrayPtr> pieces) + KJ_WARN_UNUSED_RESULT = 0; + + virtual Maybe> tryPumpFrom( + AsyncInputStream& input, uint64_t amount = kj::maxValue); + // Implements double-dispatch for AsyncInputStream::pumpTo(). + // + // This method should only be called from within an implementation of pumpTo(). + // + // This method examines the type of `input` to find optimized ways to pump data from it to this + // output stream. If it finds one, it performs the pump. Otherwise, it returns null. + // + // The default implementation always returns null. +}; + +class AsyncIoStream: public AsyncInputStream, public AsyncOutputStream { + // A combination input and output stream. + +public: + virtual void shutdownWrite() = 0; + // Cleanly shut down just the write end of the stream, while keeping the read end open. + + virtual void abortRead() {} + // Similar to shutdownWrite, but this will shut down the read end of the stream, and should only + // be called when an error has occurred. + + virtual void getsockopt(int level, int option, void* value, uint* length); + virtual void setsockopt(int level, int option, const void* value, uint length); + // Corresponds to getsockopt() and setsockopt() syscalls. Will throw an "unimplemented" exception + // if the stream is not a socket or the option is not appropriate for the socket type. The + // default implementations always throw "unimplemented". + + virtual void getsockname(struct sockaddr* addr, uint* length); + virtual void getpeername(struct sockaddr* addr, uint* length); + // Corresponds to getsockname() and getpeername() syscalls. Will throw an "unimplemented" + // exception if the stream is not a socket. The default implementations always throw + // "unimplemented". + // + // Note that we don't provide methods that return NetworkAddress because it usually wouldn't + // be useful. You can't connect() to or listen() on these addresses, obviously, because they are + // ephemeral addresses for a single connection. +}; + +struct OneWayPipe { + // A data pipe with an input end and an output end. (Typically backed by pipe() system call.) + + Own in; + Own out; +}; + +struct TwoWayPipe { + // A data pipe that supports sending in both directions. Each end's output sends data to the + // other end's input. (Typically backed by socketpair() system call.) + + Own ends[2]; +}; + +class ConnectionReceiver { + // Represents a server socket listening on a port. + +public: + virtual Promise> accept() = 0; + // Accept the next incoming connection. + + virtual uint getPort() = 0; + // Gets the port number, if applicable (i.e. if listening on IP). This is useful if you didn't + // specify a port when constructing the NetworkAddress -- one will have been assigned + // automatically. + + virtual void getsockopt(int level, int option, void* value, uint* length); + virtual void setsockopt(int level, int option, const void* value, uint length); + // Same as the methods of AsyncIoStream. +}; + +// ======================================================================================= +// Datagram I/O + +class AncillaryMessage { + // Represents an ancillary message (aka control message) received using the recvmsg() system + // call (or equivalent). Most apps will not use this. + +public: + inline AncillaryMessage(int level, int type, ArrayPtr data); + AncillaryMessage() = default; + + inline int getLevel() const; + // Originating protocol / socket level. + + inline int getType() const; + // Protocol-specific message type. + + template + inline Maybe as(); + // Interpret the ancillary message as the given struct type. Most ancillary messages are some + // sort of struct, so this is a convenient way to access it. Returns nullptr if the message + // is smaller than the struct -- this can happen if the message was truncated due to + // insufficient ancillary buffer space. + + template + inline ArrayPtr asArray(); + // Interpret the ancillary message as an array of items. If the message size does not evenly + // divide into elements of type T, the remainder is discarded -- this can happen if the message + // was truncated due to insufficient ancillary buffer space. + +private: + int level; + int type; + ArrayPtr data; + // Message data. In most cases you should use `as()` or `asArray()`. +}; + +class DatagramReceiver { + // Class encapsulating the recvmsg() system call. You must specify the DatagramReceiver's + // capacity in advance; if a received packet is larger than the capacity, it will be truncated. + +public: + virtual Promise receive() = 0; + // Receive a new message, overwriting this object's content. + // + // receive() may reuse the same buffers for content and ancillary data with each call. + + template + struct MaybeTruncated { + T value; + + bool isTruncated; + // True if the Receiver's capacity was insufficient to receive the value and therefore the + // value is truncated. + }; + + virtual MaybeTruncated> getContent() = 0; + // Get the content of the datagram. + + virtual MaybeTruncated> getAncillary() = 0; + // Ancilarry messages received with the datagram. See the recvmsg() system call and the cmsghdr + // struct. Most apps don't need this. + // + // If the returned value is truncated, then the last message in the array may itself be + // truncated, meaning its as() method will return nullptr or its asArray() method will + // return fewer elements than expected. Truncation can also mean that additional messages were + // available but discarded. + + virtual NetworkAddress& getSource() = 0; + // Get the datagram sender's address. + + struct Capacity { + size_t content = 8192; + // How much space to allocate for the datagram content. If a datagram is received that is + // larger than this, it will be truncated, with no way to recover the tail. + + size_t ancillary = 0; + // How much space to allocate for ancillary messages. As with content, if the ancillary data + // is larger than this, it will be truncated. + }; +}; + +class DatagramPort { +public: + virtual Promise send(const void* buffer, size_t size, NetworkAddress& destination) = 0; + virtual Promise send(ArrayPtr> pieces, + NetworkAddress& destination) = 0; + + virtual Own makeReceiver( + DatagramReceiver::Capacity capacity = DatagramReceiver::Capacity()) = 0; + // Create a new `Receiver` that can be used to receive datagrams. `capacity` specifies how much + // space to allocate for the received message. The `DatagramPort` must outlive the `Receiver`. + + virtual uint getPort() = 0; + // Gets the port number, if applicable (i.e. if listening on IP). This is useful if you didn't + // specify a port when constructing the NetworkAddress -- one will have been assigned + // automatically. + + virtual void getsockopt(int level, int option, void* value, uint* length); + virtual void setsockopt(int level, int option, const void* value, uint length); + // Same as the methods of AsyncIoStream. +}; + +// ======================================================================================= +// Networks + +class NetworkAddress { + // Represents a remote address to which the application can connect. + +public: + virtual Promise> connect() = 0; + // Make a new connection to this address. + // + // The address must not be a wildcard ("*"). If it is an IP address, it must have a port number. + + virtual Own listen() = 0; + // Listen for incoming connections on this address. + // + // The address must be local. + + virtual Own bindDatagramPort(); + // Open this address as a datagram (e.g. UDP) port. + // + // The address must be local. + + virtual Own clone() = 0; + // Returns an equivalent copy of this NetworkAddress. + + virtual String toString() = 0; + // Produce a human-readable string which hopefully can be passed to Network::parseAddress() + // to reproduce this address, although whether or not that works of course depends on the Network + // implementation. This should be called only to display the address to human users, who will + // hopefully know what they are able to do with it. +}; + +class Network { + // Factory for NetworkAddress instances, representing the network services offered by the + // operating system. + // + // This interface typically represents broad authority, and well-designed code should limit its + // use to high-level startup code and user interaction. Low-level APIs should accept + // NetworkAddress instances directly and work from there, if at all possible. + +public: + virtual Promise> parseAddress(StringPtr addr, uint portHint = 0) = 0; + // Construct a network address from a user-provided string. The format of the address + // strings is not specified at the API level, and application code should make no assumptions + // about them. These strings should always be provided by humans, and said humans will know + // what format to use in their particular context. + // + // `portHint`, if provided, specifies the "standard" IP port number for the application-level + // service in play. If the address turns out to be an IP address (v4 or v6), and it lacks a + // port number, this port will be used. If `addr` lacks a port number *and* `portHint` is + // omitted, then the returned address will only support listen() and bindDatagramPort() + // (not connect()), and an unused port will be chosen each time one of those methods is called. + + virtual Own getSockaddr(const void* sockaddr, uint len) = 0; + // Construct a network address from a legacy struct sockaddr. +}; + +// ======================================================================================= +// I/O Provider + +class AsyncIoProvider { + // Class which constructs asynchronous wrappers around the operating system's I/O facilities. + // + // Generally, the implementation of this interface must integrate closely with a particular + // `EventLoop` implementation. Typically, the EventLoop implementation itself will provide + // an AsyncIoProvider. + +public: + virtual OneWayPipe newOneWayPipe() = 0; + // Creates an input/output stream pair representing the ends of a one-way pipe (e.g. created with + // the pipe(2) system call). + + virtual TwoWayPipe newTwoWayPipe() = 0; + // Creates two AsyncIoStreams representing the two ends of a two-way pipe (e.g. created with + // socketpair(2) system call). Data written to one end can be read from the other. + + virtual Network& getNetwork() = 0; + // Creates a new `Network` instance representing the networks exposed by the operating system. + // + // DO NOT CALL THIS except at the highest levels of your code, ideally in the main() function. If + // you call this from low-level code, then you are preventing higher-level code from injecting an + // alternative implementation. Instead, if your code needs to use network functionality, it + // should ask for a `Network` as a constructor or method parameter, so that higher-level code can + // chose what implementation to use. The system network is essentially a singleton. See: + // http://www.object-oriented-security.org/lets-argue/singletons + // + // Code that uses the system network should not make any assumptions about what kinds of + // addresses it will parse, as this could differ across platforms. String addresses should come + // strictly from the user, who will know how to write them correctly for their system. + // + // With that said, KJ currently supports the following string address formats: + // - IPv4: "1.2.3.4", "1.2.3.4:80" + // - IPv6: "1234:5678::abcd", "[1234:5678::abcd]:80" + // - Local IP wildcard (covers both v4 and v6): "*", "*:80" + // - Symbolic names: "example.com", "example.com:80", "example.com:http", "1.2.3.4:http" + // - Unix domain: "unix:/path/to/socket" + + struct PipeThread { + // A combination of a thread and a two-way pipe that communicates with that thread. + // + // The fields are intentionally ordered so that the pipe will be destroyed (and therefore + // disconnected) before the thread is destroyed (and therefore joined). Thus if the thread + // arranges to exit when it detects disconnect, destruction should be clean. + + Own thread; + Own pipe; + }; + + virtual PipeThread newPipeThread( + Function startFunc) = 0; + // Create a new thread and set up a two-way pipe (socketpair) which can be used to communicate + // with it. One end of the pipe is passed to the thread's start function and the other end of + // the pipe is returned. The new thread also gets its own `AsyncIoProvider` instance and will + // already have an active `EventLoop` when `startFunc` is called. + // + // TODO(someday): I'm not entirely comfortable with this interface. It seems to be doing too + // much at once but I'm not sure how to cleanly break it down. + + virtual Timer& getTimer() = 0; + // Returns a `Timer` based on real time. Time does not pass while event handlers are running -- + // it only updates when the event loop polls for system events. This means that calling `now()` + // on this timer does not require a system call. + // + // This timer is not affected by changes to the system date. It is unspecified whether the timer + // continues to count while the system is suspended. +}; + +class LowLevelAsyncIoProvider { + // Similar to `AsyncIoProvider`, but represents a lower-level interface that may differ on + // different operating systems. You should prefer to use `AsyncIoProvider` over this interface + // whenever possible, as `AsyncIoProvider` is portable and friendlier to dependency-injection. + // + // On Unix, this interface can be used to import native file descriptors into the async framework. + // Different implementations of this interface might work on top of different event handling + // primitives, such as poll vs. epoll vs. kqueue vs. some higher-level event library. + // + // On Windows, this interface can be used to import native HANDLEs into the async framework. + // Different implementations of this interface might work on top of different event handling + // primitives, such as I/O completion ports vs. completion routines. + // + // TODO(port): Actually implement Windows support. + +public: + // --------------------------------------------------------------------------- + // Unix-specific stuff + + enum Flags { + // Flags controlling how to wrap a file descriptor. + + TAKE_OWNERSHIP = 1 << 0, + // The returned object should own the file descriptor, automatically closing it when destroyed. + // The close-on-exec flag will be set on the descriptor if it is not already. + // + // If this flag is not used, then the file descriptor is not automatically closed and the + // close-on-exec flag is not modified. + +#if !_WIN32 + ALREADY_CLOEXEC = 1 << 1, + // Indicates that the close-on-exec flag is known already to be set, so need not be set again. + // Only relevant when combined with TAKE_OWNERSHIP. + // + // On Linux, all system calls which yield new file descriptors have flags or variants which + // set the close-on-exec flag immediately. Unfortunately, other OS's do not. + + ALREADY_NONBLOCK = 1 << 2 + // Indicates that the file descriptor is known already to be in non-blocking mode, so the flag + // need not be set again. Otherwise, all wrap*Fd() methods will enable non-blocking mode + // automatically. + // + // On Linux, all system calls which yield new file descriptors have flags or variants which + // enable non-blocking mode immediately. Unfortunately, other OS's do not. +#endif + }; + +#if _WIN32 + typedef uintptr_t Fd; + // On Windows, the `fd` parameter to each of these methods must be a SOCKET, and must have the + // flag WSA_FLAG_OVERLAPPED (which socket() uses by default, but WSASocket() wants you to specify + // explicitly). +#else + typedef int Fd; + // On Unix, any arbitrary file descriptor is supported. +#endif + + virtual Own wrapInputFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncInputStream wrapping a file descriptor. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapOutputFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncOutputStream wrapping a file descriptor. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapSocketFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncIoStream wrapping a socket file descriptor. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Promise> wrapConnectingSocketFd( + Fd fd, const struct sockaddr* addr, uint addrlen, uint flags = 0) = 0; + // Create an AsyncIoStream wrapping a socket and initiate a connection to the given address. + // The returned promise does not resolve until connection has completed. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapListenSocketFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncIoStream wrapping a listen socket file descriptor. This socket should already + // have had `bind()` and `listen()` called on it, so it's ready for `accept()`. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapDatagramSocketFd(Fd fd, uint flags = 0); + + virtual Timer& getTimer() = 0; + // Returns a `Timer` based on real time. Time does not pass while event handlers are running -- + // it only updates when the event loop polls for system events. This means that calling `now()` + // on this timer does not require a system call. + // + // This timer is not affected by changes to the system date. It is unspecified whether the timer + // continues to count while the system is suspended. +}; + +Own newAsyncIoProvider(LowLevelAsyncIoProvider& lowLevel); +// Make a new AsyncIoProvider wrapping a `LowLevelAsyncIoProvider`. + +struct AsyncIoContext { + Own lowLevelProvider; + Own provider; + WaitScope& waitScope; + +#if _WIN32 + Win32EventPort& win32EventPort; +#else + UnixEventPort& unixEventPort; + // TEMPORARY: Direct access to underlying UnixEventPort, mainly for waiting on signals. This + // field will go away at some point when we have a chance to improve these interfaces. +#endif +}; + +AsyncIoContext setupAsyncIo(); +// Convenience method which sets up the current thread with everything it needs to do async I/O. +// The returned objects contain an `EventLoop` which is wrapping an appropriate `EventPort` for +// doing I/O on the host system, so everything is ready for the thread to start making async calls +// and waiting on promises. +// +// You would typically call this in your main() loop or in the start function of a thread. +// Example: +// +// int main() { +// auto ioContext = kj::setupAsyncIo(); +// +// // Now we can call an async function. +// Promise textPromise = getHttp(*ioContext.provider, "http://example.com"); +// +// // And we can wait for the promise to complete. Note that you can only use `wait()` +// // from the top level, not from inside a promise callback. +// String text = textPromise.wait(ioContext.waitScope); +// print(text); +// return 0; +// } +// +// WARNING: An AsyncIoContext can only be used in the thread and process that created it. In +// particular, note that after a fork(), an AsyncIoContext created in the parent process will +// not work correctly in the child, even if the parent ceases to use its copy. In particular +// note that this means that server processes which daemonize themselves at startup must wait +// until after daemonization to create an AsyncIoContext. + +// ======================================================================================= +// inline implementation details + +inline AncillaryMessage::AncillaryMessage( + int level, int type, ArrayPtr data) + : level(level), type(type), data(data) {} + +inline int AncillaryMessage::getLevel() const { return level; } +inline int AncillaryMessage::getType() const { return type; } + +template +inline Maybe AncillaryMessage::as() { + if (data.size() >= sizeof(T)) { + return *reinterpret_cast(data.begin()); + } else { + return nullptr; + } +} + +template +inline ArrayPtr AncillaryMessage::asArray() { + return arrayPtr(reinterpret_cast(data.begin()), data.size() / sizeof(T)); +} + +} // namespace kj + +#endif // KJ_ASYNC_IO_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-prelude.h b/phonelibs/capnp-cpp/include/kj/async-prelude.h new file mode 100644 index 00000000000000..0a5843f88a4d77 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-prelude.h @@ -0,0 +1,218 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains a bunch of internal declarations that must appear before async.h can start. +// We don't define these directly in async.h because it makes the file hard to read. + +#ifndef KJ_ASYNC_PRELUDE_H_ +#define KJ_ASYNC_PRELUDE_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "exception.h" +#include "tuple.h" + +namespace kj { + +class EventLoop; +template +class Promise; +class WaitScope; + +template +Promise> joinPromises(Array>&& promises); +Promise joinPromises(Array>&& promises); + +namespace _ { // private + +template struct JoinPromises_ { typedef T Type; }; +template struct JoinPromises_> { typedef T Type; }; + +template +using JoinPromises = typename JoinPromises_::Type; +// If T is Promise, resolves to U, otherwise resolves to T. +// +// TODO(cleanup): Rename to avoid confusion with joinPromises() call which is completely +// unrelated. + +class PropagateException { + // A functor which accepts a kj::Exception as a parameter and returns a broken promise of + // arbitrary type which simply propagates the exception. +public: + class Bottom { + public: + Bottom(Exception&& exception): exception(kj::mv(exception)) {} + + Exception asException() { return kj::mv(exception); } + + private: + Exception exception; + }; + + Bottom operator()(Exception&& e) { + return Bottom(kj::mv(e)); + } + Bottom operator()(const Exception& e) { + return Bottom(kj::cp(e)); + } +}; + +template +struct ReturnType_ { typedef decltype(instance()(instance())) Type; }; +template +struct ReturnType_ { typedef decltype(instance()()) Type; }; + +template +using ReturnType = typename ReturnType_::Type; +// The return type of functor Func given a parameter of type T, with the special exception that if +// T is void, this is the return type of Func called with no arguments. + +template struct SplitTuplePromise_ { typedef Promise Type; }; +template +struct SplitTuplePromise_> { + typedef kj::Tuple>...> Type; +}; + +template +using SplitTuplePromise = typename SplitTuplePromise_::Type; +// T -> Promise +// Tuple -> Tuple> + +struct Void {}; +// Application code should NOT refer to this! See `kj::READY_NOW` instead. + +template struct FixVoid_ { typedef T Type; }; +template <> struct FixVoid_ { typedef Void Type; }; +template using FixVoid = typename FixVoid_::Type; +// FixVoid is just T unless T is void in which case it is _::Void (an empty struct). + +template struct UnfixVoid_ { typedef T Type; }; +template <> struct UnfixVoid_ { typedef void Type; }; +template using UnfixVoid = typename UnfixVoid_::Type; +// UnfixVoid is the opposite of FixVoid. + +template +struct MaybeVoidCaller { + // Calls the function converting a Void input to an empty parameter list and a void return + // value to a Void output. + + template + static inline Out apply(Func& func, In&& in) { + return func(kj::mv(in)); + } +}; +template +struct MaybeVoidCaller { + template + static inline Out apply(Func& func, In& in) { + return func(in); + } +}; +template +struct MaybeVoidCaller { + template + static inline Out apply(Func& func, Void&& in) { + return func(); + } +}; +template +struct MaybeVoidCaller { + template + static inline Void apply(Func& func, In&& in) { + func(kj::mv(in)); + return Void(); + } +}; +template +struct MaybeVoidCaller { + template + static inline Void apply(Func& func, In& in) { + func(in); + return Void(); + } +}; +template <> +struct MaybeVoidCaller { + template + static inline Void apply(Func& func, Void&& in) { + func(); + return Void(); + } +}; + +template +inline T&& returnMaybeVoid(T&& t) { + return kj::fwd(t); +} +inline void returnMaybeVoid(Void&& v) {} + +class ExceptionOrValue; +class PromiseNode; +class ChainPromiseNode; +template +class ForkHub; + +class TaskSetImpl; + +class Event; + +class PromiseBase { +public: + kj::String trace(); + // Dump debug info about this promise. + +private: + Own node; + + PromiseBase() = default; + PromiseBase(Own&& node): node(kj::mv(node)) {} + + friend class kj::EventLoop; + friend class ChainPromiseNode; + template + friend class kj::Promise; + friend class TaskSetImpl; + template + friend Promise> kj::joinPromises(Array>&& promises); + friend Promise kj::joinPromises(Array>&& promises); +}; + +void detach(kj::Promise&& promise); +void waitImpl(Own<_::PromiseNode>&& node, _::ExceptionOrValue& result, WaitScope& waitScope); +Promise yield(); +Own neverDone(); + +class NeverDone { +public: + template + operator Promise() const { + return Promise(false, neverDone()); + } + + KJ_NORETURN(void wait(WaitScope& waitScope) const); +}; + +} // namespace _ (private) +} // namespace kj + +#endif // KJ_ASYNC_PRELUDE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-unix.h b/phonelibs/capnp-cpp/include/kj/async-unix.h new file mode 100644 index 00000000000000..06f128a50eeddb --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-unix.h @@ -0,0 +1,274 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_UNIX_H_ +#define KJ_ASYNC_UNIX_H_ + +#if _WIN32 +#error "This file is Unix-specific. On Windows, include async-win32.h instead." +#endif + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async.h" +#include "time.h" +#include "vector.h" +#include "io.h" +#include + +#if __linux__ && !__BIONIC__ && !defined(KJ_USE_EPOLL) +// Default to epoll on Linux, except on Bionic (Android) which doesn't have signalfd.h. +#define KJ_USE_EPOLL 1 +#endif + +namespace kj { + +class UnixEventPort: public EventPort { + // An EventPort implementation which can wait for events on file descriptors as well as signals. + // This API only makes sense on Unix. + // + // The implementation uses `poll()` or possibly a platform-specific API (e.g. epoll, kqueue). + // To also wait on signals without race conditions, the implementation may block signals until + // just before `poll()` while using a signal handler which `siglongjmp()`s back to just before + // the signal was unblocked, or it may use a nicer platform-specific API like signalfd. + // + // The implementation reserves a signal for internal use. By default, it uses SIGUSR1. If you + // need to use SIGUSR1 for something else, you must offer a different signal by calling + // setReservedSignal() at startup. + // + // WARNING: A UnixEventPort can only be used in the thread and process that created it. In + // particular, note that after a fork(), a UnixEventPort created in the parent process will + // not work correctly in the child, even if the parent ceases to use its copy. In particular + // note that this means that server processes which daemonize themselves at startup must wait + // until after daemonization to create a UnixEventPort. + +public: + UnixEventPort(); + ~UnixEventPort() noexcept(false); + + class FdObserver; + // Class that watches an fd for readability or writability. See definition below. + + Promise onSignal(int signum); + // When the given signal is delivered to this thread, return the corresponding siginfo_t. + // The signal must have been captured using `captureSignal()`. + // + // If `onSignal()` has not been called, the signal will remain blocked in this thread. + // Therefore, a signal which arrives before `onSignal()` was called will not be "missed" -- the + // next call to 'onSignal()' will receive it. Also, you can control which thread receives a + // process-wide signal by only calling `onSignal()` on that thread's event loop. + // + // The result of waiting on the same signal twice at once is undefined. + + static void captureSignal(int signum); + // Arranges for the given signal to be captured and handled via UnixEventPort, so that you may + // then pass it to `onSignal()`. This method is static because it registers a signal handler + // which applies process-wide. If any other threads exist in the process when `captureSignal()` + // is called, you *must* set the signal mask in those threads to block this signal, otherwise + // terrible things will happen if the signal happens to be delivered to those threads. If at + // all possible, call `captureSignal()` *before* creating threads, so that threads you create in + // the future will inherit the proper signal mask. + // + // To un-capture a signal, simply install a different signal handler and then un-block it from + // the signal mask. + + static void setReservedSignal(int signum); + // Sets the signal number which `UnixEventPort` reserves for internal use. If your application + // needs to use SIGUSR1, call this at startup (before any calls to `captureSignal()` and before + // constructing an `UnixEventPort`) to offer a different signal. + + Timer& getTimer() { return timerImpl; } + + // implements EventPort ------------------------------------------------------ + bool wait() override; + bool poll() override; + void wake() const override; + +private: + struct TimerSet; // Defined in source file to avoid STL include. + class TimerPromiseAdapter; + class SignalPromiseAdapter; + + TimerImpl timerImpl; + + SignalPromiseAdapter* signalHead = nullptr; + SignalPromiseAdapter** signalTail = &signalHead; + + TimePoint readClock(); + void gotSignal(const siginfo_t& siginfo); + + friend class TimerPromiseAdapter; + +#if KJ_USE_EPOLL + AutoCloseFd epollFd; + AutoCloseFd signalFd; + AutoCloseFd eventFd; // Used for cross-thread wakeups. + + sigset_t signalFdSigset; + // Signal mask as currently set on the signalFd. Tracked so we can detect whether or not it + // needs updating. + + bool doEpollWait(int timeout); + +#else + class PollContext; + + FdObserver* observersHead = nullptr; + FdObserver** observersTail = &observersHead; + + unsigned long long threadId; // actually pthread_t +#endif +}; + +class UnixEventPort::FdObserver { + // Object which watches a file descriptor to determine when it is readable or writable. + // + // For listen sockets, "readable" means that there is a connection to accept(). For everything + // else, it means that read() (or recv()) will return data. + // + // The presence of out-of-band data should NOT fire this event. However, the event may + // occasionally fire spuriously (when there is actually no data to read), and one thing that can + // cause such spurious events is the arrival of OOB data on certain platforms whose event + // interfaces fail to distinguish between regular and OOB data (e.g. Mac OSX). + // + // WARNING: The exact behavior of this class differs across systems, since event interfaces + // vary wildly. Be sure to read the documentation carefully and avoid depending on unspecified + // behavior. If at all possible, use the higher-level AsyncInputStream interface instead. + +public: + enum Flags { + OBSERVE_READ = 1, + OBSERVE_WRITE = 2, + OBSERVE_URGENT = 4, + OBSERVE_READ_WRITE = OBSERVE_READ | OBSERVE_WRITE + }; + + FdObserver(UnixEventPort& eventPort, int fd, uint flags); + // Begin watching the given file descriptor for readability. Only one ReadObserver may exist + // for a given file descriptor at a time. + + ~FdObserver() noexcept(false); + + KJ_DISALLOW_COPY(FdObserver); + + Promise whenBecomesReadable(); + // Resolves the next time the file descriptor transitions from having no data to read to having + // some data to read. + // + // KJ uses "edge-triggered" event notification whenever possible. As a result, it is an error + // to call this method when there is already data in the read buffer which has been there since + // prior to the last turn of the event loop or prior to creation FdWatcher. In this case, it is + // unspecified whether the promise will ever resolve -- it depends on the underlying event + // mechanism being used. + // + // In order to avoid this problem, make sure that you only call `whenBecomesReadable()` + // only at times when you know the buffer is empty. You know this for sure when one of the + // following happens: + // * read() or recv() fails with EAGAIN or EWOULDBLOCK. (You MUST have non-blocking mode + // enabled on the fd!) + // * The file descriptor is a regular byte-oriented object (like a socket or pipe), + // read() or recv() returns fewer than the number of bytes requested, and `atEndHint()` + // returns false. This can only happen if the buffer is empty but EOF is not reached. (Note, + // though, that for record-oriented file descriptors like Linux's inotify interface, this + // rule does not hold, because it could simply be that the next record did not fit into the + // space available.) + // + // It is an error to call `whenBecomesReadable()` again when the promise returned previously + // has not yet resolved. If you do this, the previous promise may throw an exception. + + inline Maybe atEndHint() { return atEnd; } + // Returns true if the event system has indicated that EOF has been received. There may still + // be data in the read buffer, but once that is gone, there's nothing left. + // + // Returns false if the event system has indicated that EOF had NOT been received as of the + // last turn of the event loop. + // + // Returns nullptr if the event system does not know whether EOF has been reached. In this + // case, the only way to know for sure is to call read() or recv() and check if it returns + // zero. + // + // This hint may be useful as an optimization to avoid an unnecessary system call. + + Promise whenBecomesWritable(); + // Resolves the next time the file descriptor transitions from having no space available in the + // write buffer to having some space available. + // + // KJ uses "edge-triggered" event notification whenever possible. As a result, it is an error + // to call this method when there is already space in the write buffer which has been there + // since prior to the last turn of the event loop or prior to creation FdWatcher. In this case, + // it is unspecified whether the promise will ever resolve -- it depends on the underlying + // event mechanism being used. + // + // In order to avoid this problem, make sure that you only call `whenBecomesWritable()` + // only at times when you know the buffer is full. You know this for sure when one of the + // following happens: + // * write() or send() fails with EAGAIN or EWOULDBLOCK. (You MUST have non-blocking mode + // enabled on the fd!) + // * write() or send() succeeds but accepts fewer than the number of bytes provided. This can + // only happen if the buffer is full. + // + // It is an error to call `whenBecomesWritable()` again when the promise returned previously + // has not yet resolved. If you do this, the previous promise may throw an exception. + + Promise whenUrgentDataAvailable(); + // Resolves the next time the file descriptor's read buffer contains "urgent" data. + // + // The conditions for availability of urgent data are specific to the file descriptor's + // underlying implementation. + // + // It is an error to call `whenUrgentDataAvailable()` again when the promise returned previously + // has not yet resolved. If you do this, the previous promise may throw an exception. + // + // WARNING: This has some known weird behavior on macOS. See + // https://github.com/sandstorm-io/capnproto/issues/374. + +private: + UnixEventPort& eventPort; + int fd; + uint flags; + + kj::Maybe>> readFulfiller; + kj::Maybe>> writeFulfiller; + kj::Maybe>> urgentFulfiller; + // Replaced each time `whenBecomesReadable()` or `whenBecomesWritable()` is called. Reverted to + // null every time an event is fired. + + Maybe atEnd; + + void fire(short events); + +#if !KJ_USE_EPOLL + FdObserver* next; + FdObserver** prev; + // Linked list of observers which currently have a non-null readFulfiller or writeFulfiller. + // If `prev` is null then the observer is not currently in the list. + + short getEventMask(); +#endif + + friend class UnixEventPort; +}; + +} // namespace kj + +#endif // KJ_ASYNC_UNIX_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-win32.h b/phonelibs/capnp-cpp/include/kj/async-win32.h new file mode 100644 index 00000000000000..b70c42e016c5ba --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-win32.h @@ -0,0 +1,234 @@ +// Copyright (c) 2016 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_WIN32_H_ +#define KJ_ASYNC_WIN32_H_ + +#if !_WIN32 +#error "This file is Windows-specific. On Unix, include async-unix.h instead." +#endif + +#include "async.h" +#include "time.h" +#include "io.h" +#include +#include + +// Include windows.h as lean as possible. (If you need more of the Windows API for your app, +// #include windows.h yourself before including this header.) +#define WIN32_LEAN_AND_MEAN 1 +#define NOSERVICE 1 +#define NOMCX 1 +#define NOIME 1 +#include +#include "windows-sanity.h" + +namespace kj { + +class Win32EventPort: public EventPort { + // Abstract base interface for EventPorts that can listen on Win32 event types. Due to the + // absurd complexity of the Win32 API, it's not possible to standardize on a single + // implementation of EventPort. In particular, there is no way for a single thread to use I/O + // completion ports (the most efficient way of handling I/O) while at the same time waiting for + // signalable handles or UI messages. + // + // Note that UI messages are not supported at all by this interface because the message queue + // is implemented by user32.dll and we want libkj to depend only on kernel32.dll. A separate + // compat library could provide a Win32EventPort implementation that works with the UI message + // queue. + +public: + // --------------------------------------------------------------------------- + // overlapped I/O + + struct IoResult { + DWORD errorCode; + DWORD bytesTransferred; + }; + + class IoOperation { + public: + virtual LPOVERLAPPED getOverlapped() = 0; + // Gets the OVERLAPPED structure to pass to the Win32 I/O call. Do NOT modify it; just pass it + // on. + + virtual Promise onComplete() = 0; + // After making the Win32 call, if the return value indicates that the operation was + // successfully queued (i.e. the completion event will definitely occur), call this to wait + // for completion. + // + // You MUST call this if the operation was successfully queued, and you MUST NOT call this + // otherwise. If the Win32 call failed (without queuing any operation or event) then you should + // simply drop the IoOperation object. + // + // Dropping the returned Promise cancels the operation via Win32's CancelIoEx(). The destructor + // will wait for the cancellation to complete, such that after dropping the proimse it is safe + // to free the buffer that the operation was reading from / writing to. + // + // You may safely drop the `IoOperation` while still waiting for this promise. You may not, + // however, drop the `IoObserver`. + }; + + class IoObserver { + public: + virtual Own newOperation(uint64_t offset) = 0; + // Begin an I/O operation. For file operations, `offset` is the offset within the file at + // which the operation will start. For stream operations, `offset` is ignored. + }; + + virtual Own observeIo(HANDLE handle) = 0; + // Given a handle which supports overlapped I/O, arrange to receive I/O completion events via + // this EventPort. + // + // Different Win32EventPort implementations may handle this in different ways, such as by using + // completion routines (APCs) or by using I/O completion ports. The caller should not assume + // any particular technique. + // + // WARNING: It is only safe to call observeIo() on a particular handle once during its lifetime. + // You cannot observe the same handle from multiple Win32EventPorts, even if not at the same + // time. This is because the Win32 API provides no way to disassociate a handle from an I/O + // completion port once it is associated. + + // --------------------------------------------------------------------------- + // signalable handles + // + // Warning: Due to limitations in the Win32 API, implementations of EventPort may be forced to + // spawn additional threads to wait for signaled objects. This is necessary if the EventPort + // implementation is based on I/O completion ports, or if you need to wait on more than 64 + // handles at once. + + class SignalObserver { + public: + virtual Promise onSignaled() = 0; + // Returns a promise that completes the next time the handle enters the signaled state. + // + // Depending on the type of handle, the handle may automatically be reset to a non-signaled + // state before the promise resolves. The underlying implementaiton uses WaitForSingleObject() + // or an equivalent wait call, so check the documentation for that to understand the semantics. + // + // If the handle is a mutex and it is abandoned without being unlocked, the promise breaks with + // an exception. + + virtual Promise onSignaledOrAbandoned() = 0; + // Like onSingaled(), but instead of throwing when a mutex is abandoned, resolves to `true`. + // Resolves to `false` for non-abandoned signals. + }; + + virtual Own observeSignalState(HANDLE handle) = 0; + // Given a handle that supports waiting for it to become "signaled" via WaitForSingleObject(), + // return an object that can wait for this state using the EventPort. + + // --------------------------------------------------------------------------- + // APCs + + virtual void allowApc() = 0; + // If this is ever called, the Win32EventPort will switch modes so that APCs can be scheduled + // on the thread, e.g. through the Win32 QueueUserAPC() call. In the future, this may be enabled + // by default. However, as of this writing, Wine does not support the necessary + // GetQueuedCompletionStatusEx() call, thus allowApc() breaks Wine support. (Tested on Wine + // 1.8.7.) + // + // If the event port implementation can't support APCs for some reason, this throws. + + // --------------------------------------------------------------------------- + // time + + virtual Timer& getTimer() = 0; +}; + +class Win32WaitObjectThreadPool { + // Helper class that implements Win32EventPort::observeSignalState() by spawning additional + // threads as needed to perform the actual waiting. + // + // This class is intended to be used to assist in building Win32EventPort implementations. + +public: + Win32WaitObjectThreadPool(uint mainThreadCount = 0); + // `mainThreadCount` indicates the number of objects the main thread is able to listen on + // directly. Typically this would be zero (e.g. if the main thread watches an I/O completion + // port) or MAXIMUM_WAIT_OBJECTS (e.g. if the main thread is a UI thread but can use + // MsgWaitForMultipleObjectsEx() to wait on some handles at the same time as messages). + + Own observeSignalState(HANDLE handle); + // Implemetns Win32EventPort::observeSignalState(). + + uint prepareMainThreadWait(HANDLE* handles[]); + // Call immediately before invoking WaitForMultipleObjects() or similar in the main thread. + // Fills in `handles` with the handle pointers to wait on, and returns the number of handles + // in this array. (The array should be allocated to be at least the size passed to the + // constructor). + // + // There's no need to call this if `mainThreadCount` as passed to the constructor was zero. + + bool finishedMainThreadWait(DWORD returnCode); + // Call immediately after invoking WaitForMultipleObjects() or similar in the main thread, + // passing the value returend by that call. Returns true if the event indicated by `returnCode` + // has been handled (i.e. it was WAIT_OBJECT_n or WAIT_ABANDONED_n where n is in-range for the + // last call to prepareMainThreadWait()). +}; + +class Win32IocpEventPort final: public Win32EventPort { + // An EventPort implementation which uses Windows I/O completion ports to listen for events. + // + // With this implementation, observeSignalState() requires spawning a separate thread. + +public: + Win32IocpEventPort(); + ~Win32IocpEventPort() noexcept(false); + + // implements EventPort ------------------------------------------------------ + bool wait() override; + bool poll() override; + void wake() const override; + + // implements Win32IocpEventPort --------------------------------------------- + Own observeIo(HANDLE handle) override; + Own observeSignalState(HANDLE handle) override; + Timer& getTimer() override { return timerImpl; } + void allowApc() override { isAllowApc = true; } + +private: + class IoPromiseAdapter; + class IoOperationImpl; + class IoObserverImpl; + + AutoCloseHandle iocp; + AutoCloseHandle thread; + Win32WaitObjectThreadPool waitThreads; + TimerImpl timerImpl; + mutable std::atomic sentWake {false}; + bool isAllowApc = false; + + static TimePoint readClock(); + + void waitIocp(DWORD timeoutMs); + // Wait on the I/O completion port for up to timeoutMs and pump events. Does not advance the + // timer; caller must do that. + + bool receivedWake(); + + static AutoCloseHandle newIocpHandle(); + static AutoCloseHandle openCurrentThread(); +}; + +} // namespace kj + +#endif // KJ_ASYNC_WIN32_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async.h b/phonelibs/capnp-cpp/include/kj/async.h new file mode 100644 index 00000000000000..5a9d9bdae717dc --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async.h @@ -0,0 +1,682 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_H_ +#define KJ_ASYNC_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async-prelude.h" +#include "exception.h" +#include "refcount.h" + +namespace kj { + +class EventLoop; +class WaitScope; + +template +class Promise; +template +class ForkedPromise; +template +class PromiseFulfiller; +template +struct PromiseFulfillerPair; + +template +using PromiseForResult = Promise<_::JoinPromises<_::ReturnType>>; +// Evaluates to the type of Promise for the result of calling functor type Func with parameter type +// T. If T is void, then the promise is for the result of calling Func with no arguments. If +// Func itself returns a promise, the promises are joined, so you never get Promise>. + +// ======================================================================================= +// Promises + +template +class Promise: protected _::PromiseBase { + // The basic primitive of asynchronous computation in KJ. Similar to "futures", but designed + // specifically for event loop concurrency. Similar to E promises and JavaScript Promises/A. + // + // A Promise represents a promise to produce a value of type T some time in the future. Once + // that value has been produced, the promise is "fulfilled". Alternatively, a promise can be + // "broken", with an Exception describing what went wrong. You may implicitly convert a value of + // type T to an already-fulfilled Promise. You may implicitly convert the constant + // `kj::READY_NOW` to an already-fulfilled Promise. You may also implicitly convert a + // `kj::Exception` to an already-broken promise of any type. + // + // Promises are linear types -- they are moveable but not copyable. If a Promise is destroyed + // or goes out of scope (without being moved elsewhere), any ongoing asynchronous operations + // meant to fulfill the promise will be canceled if possible. All methods of `Promise` (unless + // otherwise noted) actually consume the promise in the sense of move semantics. (Arguably they + // should be rvalue-qualified, but at the time this interface was created compilers didn't widely + // support that yet and anyway it would be pretty ugly typing kj::mv(promise).whatever().) If + // you want to use one Promise in two different places, you must fork it with `fork()`. + // + // To use the result of a Promise, you must call `then()` and supply a callback function to + // call with the result. `then()` returns another promise, for the result of the callback. + // Any time that this would result in Promise>, the promises are collapsed into a + // simple Promise that first waits for the outer promise, then the inner. Example: + // + // // Open a remote file, read the content, and then count the + // // number of lines of text. + // // Note that none of the calls here block. `file`, `content` + // // and `lineCount` are all initialized immediately before any + // // asynchronous operations occur. The lambda callbacks are + // // called later. + // Promise> file = openFtp("ftp://host/foo/bar"); + // Promise content = file.then( + // [](Own file) -> Promise { + // return file.readAll(); + // }); + // Promise lineCount = content.then( + // [](String text) -> int { + // uint count = 0; + // for (char c: text) count += (c == '\n'); + // return count; + // }); + // + // For `then()` to work, the current thread must have an active `EventLoop`. Each callback + // is scheduled to execute in that loop. Since `then()` schedules callbacks only on the current + // thread's event loop, you do not need to worry about two callbacks running at the same time. + // You will need to set up at least one `EventLoop` at the top level of your program before you + // can use promises. + // + // To adapt a non-Promise-based asynchronous API to promises, use `newAdaptedPromise()`. + // + // Systems using promises should consider supporting the concept of "pipelining". Pipelining + // means allowing a caller to start issuing method calls against a promised object before the + // promise has actually been fulfilled. This is particularly useful if the promise is for a + // remote object living across a network, as this can avoid round trips when chaining a series + // of calls. It is suggested that any class T which supports pipelining implement a subclass of + // Promise which adds "eventual send" methods -- methods which, when called, say "please + // invoke the corresponding method on the promised value once it is available". These methods + // should in turn return promises for the eventual results of said invocations. Cap'n Proto, + // for example, implements the type `RemotePromise` which supports pipelining RPC requests -- see + // `capnp/capability.h`. + // + // KJ Promises are based on E promises: + // http://wiki.erights.org/wiki/Walnut/Distributed_Computing#Promises + // + // KJ Promises are also inspired in part by the evolving standards for JavaScript/ECMAScript + // promises, which are themselves influenced by E promises: + // http://promisesaplus.com/ + // https://github.com/domenic/promises-unwrapping + +public: + Promise(_::FixVoid value); + // Construct an already-fulfilled Promise from a value of type T. For non-void promises, the + // parameter type is simply T. So, e.g., in a function that returns `Promise`, you can + // say `return 123;` to return a promise that is already fulfilled to 123. + // + // For void promises, use `kj::READY_NOW` as the value, e.g. `return kj::READY_NOW`. + + Promise(kj::Exception&& e); + // Construct an already-broken Promise. + + inline Promise(decltype(nullptr)) {} + + template + PromiseForResult then(Func&& func, ErrorFunc&& errorHandler = _::PropagateException()) + KJ_WARN_UNUSED_RESULT; + // Register a continuation function to be executed when the promise completes. The continuation + // (`func`) takes the promised value (an rvalue of type `T`) as its parameter. The continuation + // may return a new value; `then()` itself returns a promise for the continuation's eventual + // result. If the continuation itself returns a `Promise`, then `then()` shall also return + // a `Promise` which first waits for the original promise, then executes the continuation, + // then waits for the inner promise (i.e. it automatically "unwraps" the promise). + // + // In all cases, `then()` returns immediately. The continuation is executed later. The + // continuation is always executed on the same EventLoop (and, therefore, the same thread) which + // called `then()`, therefore no synchronization is necessary on state shared by the continuation + // and the surrounding scope. If no EventLoop is running on the current thread, `then()` throws + // an exception. + // + // You may also specify an error handler continuation as the second parameter. `errorHandler` + // must be a functor taking a parameter of type `kj::Exception&&`. It must return the same + // type as `func` returns (except when `func` returns `Promise`, in which case `errorHandler` + // may return either `Promise` or just `U`). The default error handler simply propagates the + // exception to the returned promise. + // + // Either `func` or `errorHandler` may, of course, throw an exception, in which case the promise + // is broken. When compiled with -fno-exceptions, the framework will still detect when a + // recoverable exception was thrown inside of a continuation and will consider the promise + // broken even though a (presumably garbage) result was returned. + // + // If the returned promise is destroyed before the callback runs, the callback will be canceled + // (it will never run). + // + // Note that `then()` -- like all other Promise methods -- consumes the promise on which it is + // called, in the sense of move semantics. After returning, the original promise is no longer + // valid, but `then()` returns a new promise. + // + // *Advanced implementation tips:* Most users will never need to worry about the below, but + // it is good to be aware of. + // + // As an optimization, if the callback function `func` does _not_ return another promise, then + // execution of `func` itself may be delayed until its result is known to be needed. The + // expectation here is that `func` is just doing some transformation on the results, not + // scheduling any other actions, therefore the system doesn't need to be proactive about + // evaluating it. This way, a chain of trivial then() transformations can be executed all at + // once without repeatedly re-scheduling through the event loop. Use the `eagerlyEvaluate()` + // method to suppress this behavior. + // + // On the other hand, if `func` _does_ return another promise, then the system evaluates `func` + // as soon as possible, because the promise it returns might be for a newly-scheduled + // long-running asynchronous task. + // + // As another optimization, when a callback function registered with `then()` is actually + // scheduled, it is scheduled to occur immediately, preempting other work in the event queue. + // This allows a long chain of `then`s to execute all at once, improving cache locality by + // clustering operations on the same data. However, this implies that starvation can occur + // if a chain of `then()`s takes a very long time to execute without ever stopping to wait for + // actual I/O. To solve this, use `kj::evalLater()` to yield control; this way, all other events + // in the queue will get a chance to run before your callback is executed. + + Promise ignoreResult() KJ_WARN_UNUSED_RESULT { return then([](T&&) {}); } + // Convenience method to convert the promise to a void promise by ignoring the return value. + // + // You must still wait on the returned promise if you want the task to execute. + + template + Promise catch_(ErrorFunc&& errorHandler) KJ_WARN_UNUSED_RESULT; + // Equivalent to `.then(identityFunc, errorHandler)`, where `identifyFunc` is a function that + // just returns its input. + + T wait(WaitScope& waitScope); + // Run the event loop until the promise is fulfilled, then return its result. If the promise + // is rejected, throw an exception. + // + // wait() is primarily useful at the top level of a program -- typically, within the function + // that allocated the EventLoop. For example, a program that performs one or two RPCs and then + // exits would likely use wait() in its main() function to wait on each RPC. On the other hand, + // server-side code generally cannot use wait(), because it has to be able to accept multiple + // requests at once. + // + // If the promise is rejected, `wait()` throws an exception. If the program was compiled without + // exceptions (-fno-exceptions), this will usually abort. In this case you really should first + // use `then()` to set an appropriate handler for the exception case, so that the promise you + // actually wait on never throws. + // + // `waitScope` is an object proving that the caller is in a scope where wait() is allowed. By + // convention, any function which might call wait(), or which might call another function which + // might call wait(), must take `WaitScope&` as one of its parameters. This is needed for two + // reasons: + // * `wait()` is not allowed during an event callback, because event callbacks are themselves + // called during some other `wait()`, and such recursive `wait()`s would only be able to + // complete in LIFO order, which might mean that the outer `wait()` ends up waiting longer + // than it is supposed to. To prevent this, a `WaitScope` cannot be constructed or used during + // an event callback. + // * Since `wait()` runs the event loop, unrelated event callbacks may execute before `wait()` + // returns. This means that anyone calling `wait()` must be reentrant -- state may change + // around them in arbitrary ways. Therefore, callers really need to know if a function they + // are calling might wait(), and the `WaitScope&` parameter makes this clear. + // + // TODO(someday): Implement fibers, and let them call wait() even when they are handling an + // event. + + ForkedPromise fork() KJ_WARN_UNUSED_RESULT; + // Forks the promise, so that multiple different clients can independently wait on the result. + // `T` must be copy-constructable for this to work. Or, in the special case where `T` is + // `Own`, `U` must have a method `Own addRef()` which returns a new reference to the same + // (or an equivalent) object (probably implemented via reference counting). + + _::SplitTuplePromise split(); + // Split a promise for a tuple into a tuple of promises. + // + // E.g. if you have `Promise>`, `split()` returns + // `kj::Tuple, Promise>`. + + Promise exclusiveJoin(Promise&& other) KJ_WARN_UNUSED_RESULT; + // Return a new promise that resolves when either the original promise resolves or `other` + // resolves (whichever comes first). The promise that didn't resolve first is canceled. + + // TODO(someday): inclusiveJoin(), or perhaps just join(), which waits for both completions + // and produces a tuple? + + template + Promise attach(Attachments&&... attachments) KJ_WARN_UNUSED_RESULT; + // "Attaches" one or more movable objects (often, Owns) to the promise, such that they will + // be destroyed when the promise resolves. This is useful when a promise's callback contains + // pointers into some object and you want to make sure the object still exists when the callback + // runs -- after calling then(), use attach() to add necessary objects to the result. + + template + Promise eagerlyEvaluate(ErrorFunc&& errorHandler) KJ_WARN_UNUSED_RESULT; + Promise eagerlyEvaluate(decltype(nullptr)) KJ_WARN_UNUSED_RESULT; + // Force eager evaluation of this promise. Use this if you are going to hold on to the promise + // for awhile without consuming the result, but you want to make sure that the system actually + // processes it. + // + // `errorHandler` is a function that takes `kj::Exception&&`, like the second parameter to + // `then()`, except that it must return void. We make you specify this because otherwise it's + // easy to forget to handle errors in a promise that you never use. You may specify nullptr for + // the error handler if you are sure that ignoring errors is fine, or if you know that you'll + // eventually wait on the promise somewhere. + + template + void detach(ErrorFunc&& errorHandler); + // Allows the promise to continue running in the background until it completes or the + // `EventLoop` is destroyed. Be careful when using this: since you can no longer cancel this + // promise, you need to make sure that the promise owns all the objects it touches or make sure + // those objects outlive the EventLoop. + // + // `errorHandler` is a function that takes `kj::Exception&&`, like the second parameter to + // `then()`, except that it must return void. + // + // This function exists mainly to implement the Cap'n Proto requirement that RPC calls cannot be + // canceled unless the callee explicitly permits it. + + kj::String trace(); + // Returns a dump of debug info about this promise. Not for production use. Requires RTTI. + // This method does NOT consume the promise as other methods do. + +private: + Promise(bool, Own<_::PromiseNode>&& node): PromiseBase(kj::mv(node)) {} + // Second parameter prevent ambiguity with immediate-value constructor. + + template + friend class Promise; + friend class EventLoop; + template + friend Promise newAdaptedPromise(Params&&... adapterConstructorParams); + template + friend PromiseFulfillerPair newPromiseAndFulfiller(); + template + friend class _::ForkHub; + friend class _::TaskSetImpl; + friend Promise _::yield(); + friend class _::NeverDone; + template + friend Promise> joinPromises(Array>&& promises); + friend Promise joinPromises(Array>&& promises); +}; + +template +class ForkedPromise { + // The result of `Promise::fork()` and `EventLoop::fork()`. Allows branches to be created. + // Like `Promise`, this is a pass-by-move type. + +public: + inline ForkedPromise(decltype(nullptr)) {} + + Promise addBranch(); + // Add a new branch to the fork. The branch is equivalent to the original promise. + +private: + Own<_::ForkHub<_::FixVoid>> hub; + + inline ForkedPromise(bool, Own<_::ForkHub<_::FixVoid>>&& hub): hub(kj::mv(hub)) {} + + friend class Promise; + friend class EventLoop; +}; + +constexpr _::Void READY_NOW = _::Void(); +// Use this when you need a Promise that is already fulfilled -- this value can be implicitly +// cast to `Promise`. + +constexpr _::NeverDone NEVER_DONE = _::NeverDone(); +// The opposite of `READY_NOW`, return this when the promise should never resolve. This can be +// implicitly converted to any promise type. You may also call `NEVER_DONE.wait()` to wait +// forever (useful for servers). + +template +PromiseForResult evalLater(Func&& func) KJ_WARN_UNUSED_RESULT; +// Schedule for the given zero-parameter function to be executed in the event loop at some +// point in the near future. Returns a Promise for its result -- or, if `func()` itself returns +// a promise, `evalLater()` returns a Promise for the result of resolving that promise. +// +// Example usage: +// Promise x = evalLater([]() { return 123; }); +// +// The above is exactly equivalent to: +// Promise x = Promise(READY_NOW).then([]() { return 123; }); +// +// If the returned promise is destroyed before the callback runs, the callback will be canceled +// (never called). +// +// If you schedule several evaluations with `evalLater` during the same callback, they are +// guaranteed to be executed in order. + +template +PromiseForResult evalNow(Func&& func) KJ_WARN_UNUSED_RESULT; +// Run `func()` and return a promise for its result. `func()` executes before `evalNow()` returns. +// If `func()` throws an exception, the exception is caught and wrapped in a promise -- this is the +// main reason why `evalNow()` is useful. + +template +Promise> joinPromises(Array>&& promises); +// Join an array of promises into a promise for an array. + +// ======================================================================================= +// Hack for creating a lambda that holds an owned pointer. + +template +class CaptureByMove { +public: + inline CaptureByMove(Func&& func, MovedParam&& param) + : func(kj::mv(func)), param(kj::mv(param)) {} + + template + inline auto operator()(Params&&... params) + -> decltype(kj::instance()(kj::instance(), kj::fwd(params)...)) { + return func(kj::mv(param), kj::fwd(params)...); + } + +private: + Func func; + MovedParam param; +}; + +template +inline CaptureByMove> mvCapture(MovedParam&& param, Func&& func) { + // Hack to create a "lambda" which captures a variable by moving it rather than copying or + // referencing. C++14 generalized captures should make this obsolete, but for now in C++11 this + // is commonly needed for Promise continuations that own their state. Example usage: + // + // Own ptr = makeFoo(); + // Promise promise = callRpc(); + // promise.then(mvCapture(ptr, [](Own&& ptr, int result) { + // return ptr->finish(result); + // })); + + return CaptureByMove>(kj::fwd(func), kj::mv(param)); +} + +// ======================================================================================= +// Advanced promise construction + +template +class PromiseFulfiller { + // A callback which can be used to fulfill a promise. Only the first call to fulfill() or + // reject() matters; subsequent calls are ignored. + +public: + virtual void fulfill(T&& value) = 0; + // Fulfill the promise with the given value. + + virtual void reject(Exception&& exception) = 0; + // Reject the promise with an error. + + virtual bool isWaiting() = 0; + // Returns true if the promise is still unfulfilled and someone is potentially waiting for it. + // Returns false if fulfill()/reject() has already been called *or* if the promise to be + // fulfilled has been discarded and therefore the result will never be used anyway. + + template + bool rejectIfThrows(Func&& func); + // Call the function (with no arguments) and return true. If an exception is thrown, call + // `fulfiller.reject()` and then return false. When compiled with exceptions disabled, + // non-fatal exceptions are still detected and handled correctly. +}; + +template <> +class PromiseFulfiller { + // Specialization of PromiseFulfiller for void promises. See PromiseFulfiller. + +public: + virtual void fulfill(_::Void&& value = _::Void()) = 0; + // Call with zero parameters. The parameter is a dummy that only exists so that subclasses don't + // have to specialize for . + + virtual void reject(Exception&& exception) = 0; + virtual bool isWaiting() = 0; + + template + bool rejectIfThrows(Func&& func); +}; + +template +Promise newAdaptedPromise(Params&&... adapterConstructorParams); +// Creates a new promise which owns an instance of `Adapter` which encapsulates the operation +// that will eventually fulfill the promise. This is primarily useful for adapting non-KJ +// asynchronous APIs to use promises. +// +// An instance of `Adapter` will be allocated and owned by the returned `Promise`. A +// `PromiseFulfiller&` will be passed as the first parameter to the adapter's constructor, +// and `adapterConstructorParams` will be forwarded as the subsequent parameters. The adapter +// is expected to perform some asynchronous operation and call the `PromiseFulfiller` once +// it is finished. +// +// The adapter is destroyed when its owning Promise is destroyed. This may occur before the +// Promise has been fulfilled. In this case, the adapter's destructor should cancel the +// asynchronous operation. Once the adapter is destroyed, the fulfillment callback cannot be +// called. +// +// An adapter implementation should be carefully written to ensure that it cannot accidentally +// be left unfulfilled permanently because of an exception. Consider making liberal use of +// `PromiseFulfiller::rejectIfThrows()`. + +template +struct PromiseFulfillerPair { + Promise<_::JoinPromises> promise; + Own> fulfiller; +}; + +template +PromiseFulfillerPair newPromiseAndFulfiller(); +// Construct a Promise and a separate PromiseFulfiller which can be used to fulfill the promise. +// If the PromiseFulfiller is destroyed before either of its methods are called, the Promise is +// implicitly rejected. +// +// Although this function is easier to use than `newAdaptedPromise()`, it has the serious drawback +// that there is no way to handle cancellation (i.e. detect when the Promise is discarded). +// +// You can arrange to fulfill a promise with another promise by using a promise type for T. E.g. +// `newPromiseAndFulfiller>()` will produce a promise of type `Promise` but the +// fulfiller will be of type `PromiseFulfiller>`. Thus you pass a `Promise` to the +// `fulfill()` callback, and the promises are chained. + +// ======================================================================================= +// TaskSet + +class TaskSet { + // Holds a collection of Promises and ensures that each executes to completion. Memory + // associated with each promise is automatically freed when the promise completes. Destroying + // the TaskSet itself automatically cancels all unfinished promises. + // + // This is useful for "daemon" objects that perform background tasks which aren't intended to + // fulfill any particular external promise, but which may need to be canceled (and thus can't + // use `Promise::detach()`). The daemon object holds a TaskSet to collect these tasks it is + // working on. This way, if the daemon itself is destroyed, the TaskSet is detroyed as well, + // and everything the daemon is doing is canceled. + +public: + class ErrorHandler { + public: + virtual void taskFailed(kj::Exception&& exception) = 0; + }; + + TaskSet(ErrorHandler& errorHandler); + // `loop` will be used to wait on promises. `errorHandler` will be executed any time a task + // throws an exception, and will execute within the given EventLoop. + + ~TaskSet() noexcept(false); + + void add(Promise&& promise); + + kj::String trace(); + // Return debug info about all promises currently in the TaskSet. + +private: + Own<_::TaskSetImpl> impl; +}; + +// ======================================================================================= +// The EventLoop class + +class EventPort { + // Interfaces between an `EventLoop` and events originating from outside of the loop's thread. + // All such events come in through the `EventPort` implementation. + // + // An `EventPort` implementation may interface with low-level operating system APIs and/or other + // threads. You can also write an `EventPort` which wraps some other (non-KJ) event loop + // framework, allowing the two to coexist in a single thread. + +public: + virtual bool wait() = 0; + // Wait for an external event to arrive, sleeping if necessary. Once at least one event has + // arrived, queue it to the event loop (e.g. by fulfilling a promise) and return. + // + // This is called during `Promise::wait()` whenever the event queue becomes empty, in order to + // wait for new events to populate the queue. + // + // It is safe to return even if nothing has actually been queued, so long as calling `wait()` in + // a loop will eventually sleep. (That is to say, false positives are fine.) + // + // Returns true if wake() has been called from another thread. (Precisely, returns true if + // no previous call to wait `wait()` nor `poll()` has returned true since `wake()` was last + // called.) + + virtual bool poll() = 0; + // Check if any external events have arrived, but do not sleep. If any events have arrived, + // add them to the event queue (e.g. by fulfilling promises) before returning. + // + // This may be called during `Promise::wait()` when the EventLoop has been executing for a while + // without a break but is still non-empty. + // + // Returns true if wake() has been called from another thread. (Precisely, returns true if + // no previous call to wait `wait()` nor `poll()` has returned true since `wake()` was last + // called.) + + virtual void setRunnable(bool runnable); + // Called to notify the `EventPort` when the `EventLoop` has work to do; specifically when it + // transitions from empty -> runnable or runnable -> empty. This is typically useful when + // integrating with an external event loop; if the loop is currently runnable then you should + // arrange to call run() on it soon. The default implementation does nothing. + + virtual void wake() const; + // Wake up the EventPort's thread from another thread. + // + // Unlike all other methods on this interface, `wake()` may be called from another thread, hence + // it is `const`. + // + // Technically speaking, `wake()` causes the target thread to cease sleeping and not to sleep + // again until `wait()` or `poll()` has returned true at least once. + // + // The default implementation throws an UNIMPLEMENTED exception. +}; + +class EventLoop { + // Represents a queue of events being executed in a loop. Most code won't interact with + // EventLoop directly, but instead use `Promise`s to interact with it indirectly. See the + // documentation for `Promise`. + // + // Each thread can have at most one current EventLoop. To make an `EventLoop` current for + // the thread, create a `WaitScope`. Async APIs require that the thread has a current EventLoop, + // or they will throw exceptions. APIs that use `Promise::wait()` additionally must explicitly + // be passed a reference to the `WaitScope` to make the caller aware that they might block. + // + // Generally, you will want to construct an `EventLoop` at the top level of your program, e.g. + // in the main() function, or in the start function of a thread. You can then use it to + // construct some promises and wait on the result. Example: + // + // int main() { + // // `loop` becomes the official EventLoop for the thread. + // MyEventPort eventPort; + // EventLoop loop(eventPort); + // + // // Now we can call an async function. + // Promise textPromise = getHttp("http://example.com"); + // + // // And we can wait for the promise to complete. Note that you can only use `wait()` + // // from the top level, not from inside a promise callback. + // String text = textPromise.wait(); + // print(text); + // return 0; + // } + // + // Most applications that do I/O will prefer to use `setupAsyncIo()` from `async-io.h` rather + // than allocate an `EventLoop` directly. + +public: + EventLoop(); + // Construct an `EventLoop` which does not receive external events at all. + + explicit EventLoop(EventPort& port); + // Construct an `EventLoop` which receives external events through the given `EventPort`. + + ~EventLoop() noexcept(false); + + void run(uint maxTurnCount = maxValue); + // Run the event loop for `maxTurnCount` turns or until there is nothing left to be done, + // whichever comes first. This never calls the `EventPort`'s `sleep()` or `poll()`. It will + // call the `EventPort`'s `setRunnable(false)` if the queue becomes empty. + + bool isRunnable(); + // Returns true if run() would currently do anything, or false if the queue is empty. + +private: + EventPort& port; + + bool running = false; + // True while looping -- wait() is then not allowed. + + bool lastRunnableState = false; + // What did we last pass to port.setRunnable()? + + _::Event* head = nullptr; + _::Event** tail = &head; + _::Event** depthFirstInsertPoint = &head; + + Own<_::TaskSetImpl> daemons; + + bool turn(); + void setRunnable(bool runnable); + void enterScope(); + void leaveScope(); + + friend void _::detach(kj::Promise&& promise); + friend void _::waitImpl(Own<_::PromiseNode>&& node, _::ExceptionOrValue& result, + WaitScope& waitScope); + friend class _::Event; + friend class WaitScope; +}; + +class WaitScope { + // Represents a scope in which asynchronous programming can occur. A `WaitScope` should usually + // be allocated on the stack and serves two purposes: + // * While the `WaitScope` exists, its `EventLoop` is registered as the current loop for the + // thread. Most operations dealing with `Promise` (including all of its methods) do not work + // unless the thread has a current `EventLoop`. + // * `WaitScope` may be passed to `Promise::wait()` to synchronously wait for a particular + // promise to complete. See `Promise::wait()` for an extended discussion. + +public: + inline explicit WaitScope(EventLoop& loop): loop(loop) { loop.enterScope(); } + inline ~WaitScope() { loop.leaveScope(); } + KJ_DISALLOW_COPY(WaitScope); + +private: + EventLoop& loop; + friend class EventLoop; + friend void _::waitImpl(Own<_::PromiseNode>&& node, _::ExceptionOrValue& result, + WaitScope& waitScope); +}; + +} // namespace kj + +#include "async-inl.h" + +#endif // KJ_ASYNC_H_ diff --git a/phonelibs/capnp-cpp/include/kj/common.h b/phonelibs/capnp-cpp/include/kj/common.h new file mode 100644 index 00000000000000..4a908ae0007fd7 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/common.h @@ -0,0 +1,1400 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// Header that should be #included by everyone. +// +// This defines very simple utilities that are widely applicable. + +#ifndef KJ_COMMON_H_ +#define KJ_COMMON_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#ifndef KJ_NO_COMPILER_CHECK +#if __cplusplus < 201103L && !__CDT_PARSER__ && !_MSC_VER + #error "This code requires C++11. Either your compiler does not support it or it is not enabled." + #ifdef __GNUC__ + // Compiler claims compatibility with GCC, so presumably supports -std. + #error "Pass -std=c++11 on the compiler command line to enable C++11." + #endif +#endif + +#ifdef __GNUC__ + #if __clang__ + #if __clang_major__ < 3 || (__clang_major__ == 3 && __clang_minor__ < 2) + #warning "This library requires at least Clang 3.2." + #elif defined(__apple_build_version__) && __apple_build_version__ <= 4250028 + #warning "This library requires at least Clang 3.2. XCode 4.6's Clang, which claims to be "\ + "version 4.2 (wat?), is actually built from some random SVN revision between 3.1 "\ + "and 3.2. Unfortunately, it is insufficient for compiling this library. You can "\ + "download the real Clang 3.2 (or newer) from the Clang web site. Step-by-step "\ + "instructions can be found in Cap'n Proto's documentation: "\ + "http://kentonv.github.io/capnproto/install.html#clang_32_on_mac_osx" + #elif __cplusplus >= 201103L && !__has_include() + #warning "Your compiler supports C++11 but your C++ standard library does not. If your "\ + "system has libc++ installed (as should be the case on e.g. Mac OSX), try adding "\ + "-stdlib=libc++ to your CXXFLAGS." + #endif + #else + #if __GNUC__ < 4 || (__GNUC__ == 4 && __GNUC_MINOR__ < 7) + #warning "This library requires at least GCC 4.7." + #endif + #endif +#elif defined(_MSC_VER) + #if _MSC_VER < 1900 + #error "You need Visual Studio 2015 or better to compile this code." + #endif +#else + #warning "I don't recognize your compiler. As of this writing, Clang and GCC are the only "\ + "known compilers with enough C++11 support for this library. "\ + "#define KJ_NO_COMPILER_CHECK to make this warning go away." +#endif +#endif + +#include +#include + +#if __linux__ && __cplusplus > 201200L +// Hack around stdlib bug with C++14 that exists on some Linux systems. +// Apparently in this mode the C library decides not to define gets() but the C++ library still +// tries to import it into the std namespace. This bug has been fixed at the source but is still +// widely present in the wild e.g. on Ubuntu 14.04. +#undef _GLIBCXX_HAVE_GETS +#endif + +#if defined(_MSC_VER) +#ifndef NOMINMAX +#define NOMINMAX 1 +#endif +#include // __popcnt +#endif + +// ======================================================================================= + +namespace kj { + +typedef unsigned int uint; +typedef unsigned char byte; + +// ======================================================================================= +// Common macros, especially for common yet compiler-specific features. + +// Detect whether RTTI and exceptions are enabled, assuming they are unless we have specific +// evidence to the contrary. Clients can always define KJ_NO_RTTI or KJ_NO_EXCEPTIONS explicitly +// to override these checks. +#ifdef __GNUC__ + #if !defined(KJ_NO_RTTI) && !__GXX_RTTI + #define KJ_NO_RTTI 1 + #endif + #if !defined(KJ_NO_EXCEPTIONS) && !__EXCEPTIONS + #define KJ_NO_EXCEPTIONS 1 + #endif +#elif defined(_MSC_VER) + #if !defined(KJ_NO_RTTI) && !defined(_CPPRTTI) + #define KJ_NO_RTTI 1 + #endif + #if !defined(KJ_NO_EXCEPTIONS) && !defined(_CPPUNWIND) + #define KJ_NO_EXCEPTIONS 1 + #endif +#endif + +#if !defined(KJ_DEBUG) && !defined(KJ_NDEBUG) +// Heuristically decide whether to enable debug mode. If DEBUG or NDEBUG is defined, use that. +// Otherwise, fall back to checking whether optimization is enabled. +#if defined(DEBUG) || defined(_DEBUG) +#define KJ_DEBUG +#elif defined(NDEBUG) +#define KJ_NDEBUG +#elif __OPTIMIZE__ +#define KJ_NDEBUG +#else +#define KJ_DEBUG +#endif +#endif + +#define KJ_DISALLOW_COPY(classname) \ + classname(const classname&) = delete; \ + classname& operator=(const classname&) = delete +// Deletes the implicit copy constructor and assignment operator. + +#ifdef __GNUC__ +#define KJ_LIKELY(condition) __builtin_expect(condition, true) +#define KJ_UNLIKELY(condition) __builtin_expect(condition, false) +// Branch prediction macros. Evaluates to the condition given, but also tells the compiler that we +// expect the condition to be true/false enough of the time that it's worth hard-coding branch +// prediction. +#else +#define KJ_LIKELY(condition) (condition) +#define KJ_UNLIKELY(condition) (condition) +#endif + +#if defined(KJ_DEBUG) || __NO_INLINE__ +#define KJ_ALWAYS_INLINE(...) inline __VA_ARGS__ +// Don't force inline in debug mode. +#else +#if defined(_MSC_VER) +#define KJ_ALWAYS_INLINE(...) __forceinline __VA_ARGS__ +#else +#define KJ_ALWAYS_INLINE(...) inline __VA_ARGS__ __attribute__((always_inline)) +#endif +// Force a function to always be inlined. Apply only to the prototype, not to the definition. +#endif + +#if defined(_MSC_VER) +#define KJ_NOINLINE __declspec(noinline) +#else +#define KJ_NOINLINE __attribute__((noinline)) +#endif + +#if defined(_MSC_VER) +#define KJ_NORETURN(prototype) __declspec(noreturn) prototype +#define KJ_UNUSED +#define KJ_WARN_UNUSED_RESULT +// TODO(msvc): KJ_WARN_UNUSED_RESULT can use _Check_return_ on MSVC, but it's a prefix, so +// wrapping the whole prototype is needed. http://msdn.microsoft.com/en-us/library/jj159529.aspx +// Similarly, KJ_UNUSED could use __pragma(warning(suppress:...)), but again that's a prefix. +#else +#define KJ_NORETURN(prototype) prototype __attribute__((noreturn)) +#define KJ_UNUSED __attribute__((unused)) +#define KJ_WARN_UNUSED_RESULT __attribute__((warn_unused_result)) +#endif + +#if __clang__ +#define KJ_UNUSED_MEMBER __attribute__((unused)) +// Inhibits "unused" warning for member variables. Only Clang produces such a warning, while GCC +// complains if the attribute is set on members. +#else +#define KJ_UNUSED_MEMBER +#endif + +#if __clang__ +#define KJ_DEPRECATED(reason) \ + __attribute__((deprecated(reason))) +#define KJ_UNAVAILABLE(reason) \ + __attribute__((unavailable(reason))) +#elif __GNUC__ +#define KJ_DEPRECATED(reason) \ + __attribute__((deprecated)) +#define KJ_UNAVAILABLE(reason) +#else +#define KJ_DEPRECATED(reason) +#define KJ_UNAVAILABLE(reason) +// TODO(msvc): Again, here, MSVC prefers a prefix, __declspec(deprecated). +#endif + +namespace _ { // private + +KJ_NORETURN(void inlineRequireFailure( + const char* file, int line, const char* expectation, const char* macroArgs, + const char* message = nullptr)); + +KJ_NORETURN(void unreachable()); + +} // namespace _ (private) + +#ifdef KJ_DEBUG +#if _MSC_VER +#define KJ_IREQUIRE(condition, ...) \ + if (KJ_LIKELY(condition)); else ::kj::_::inlineRequireFailure( \ + __FILE__, __LINE__, #condition, "" #__VA_ARGS__, __VA_ARGS__) +// Version of KJ_DREQUIRE() which is safe to use in headers that are #included by users. Used to +// check preconditions inside inline methods. KJ_IREQUIRE is particularly useful in that +// it will be enabled depending on whether the application is compiled in debug mode rather than +// whether libkj is. +#else +#define KJ_IREQUIRE(condition, ...) \ + if (KJ_LIKELY(condition)); else ::kj::_::inlineRequireFailure( \ + __FILE__, __LINE__, #condition, #__VA_ARGS__, ##__VA_ARGS__) +// Version of KJ_DREQUIRE() which is safe to use in headers that are #included by users. Used to +// check preconditions inside inline methods. KJ_IREQUIRE is particularly useful in that +// it will be enabled depending on whether the application is compiled in debug mode rather than +// whether libkj is. +#endif +#else +#define KJ_IREQUIRE(condition, ...) +#endif + +#define KJ_IASSERT KJ_IREQUIRE + +#define KJ_UNREACHABLE ::kj::_::unreachable(); +// Put this on code paths that cannot be reached to suppress compiler warnings about missing +// returns. + +#if __clang__ +#define KJ_CLANG_KNOWS_THIS_IS_UNREACHABLE_BUT_GCC_DOESNT +#else +#define KJ_CLANG_KNOWS_THIS_IS_UNREACHABLE_BUT_GCC_DOESNT KJ_UNREACHABLE +#endif + +// #define KJ_STACK_ARRAY(type, name, size, minStack, maxStack) +// +// Allocate an array, preferably on the stack, unless it is too big. On GCC this will use +// variable-sized arrays. For other compilers we could just use a fixed-size array. `minStack` +// is the stack array size to use if variable-width arrays are not supported. `maxStack` is the +// maximum stack array size if variable-width arrays *are* supported. +#if __GNUC__ && !__clang__ +#define KJ_STACK_ARRAY(type, name, size, minStack, maxStack) \ + size_t name##_size = (size); \ + bool name##_isOnStack = name##_size <= (maxStack); \ + type name##_stack[name##_isOnStack ? size : 0]; \ + ::kj::Array name##_heap = name##_isOnStack ? \ + nullptr : kj::heapArray(name##_size); \ + ::kj::ArrayPtr name = name##_isOnStack ? \ + kj::arrayPtr(name##_stack, name##_size) : name##_heap +#else +#define KJ_STACK_ARRAY(type, name, size, minStack, maxStack) \ + size_t name##_size = (size); \ + bool name##_isOnStack = name##_size <= (minStack); \ + type name##_stack[minStack]; \ + ::kj::Array name##_heap = name##_isOnStack ? \ + nullptr : kj::heapArray(name##_size); \ + ::kj::ArrayPtr name = name##_isOnStack ? \ + kj::arrayPtr(name##_stack, name##_size) : name##_heap +#endif + +#define KJ_CONCAT_(x, y) x##y +#define KJ_CONCAT(x, y) KJ_CONCAT_(x, y) +#define KJ_UNIQUE_NAME(prefix) KJ_CONCAT(prefix, __LINE__) +// Create a unique identifier name. We use concatenate __LINE__ rather than __COUNTER__ so that +// the name can be used multiple times in the same macro. + +#if _MSC_VER + +#define KJ_CONSTEXPR(...) __VA_ARGS__ +// Use in cases where MSVC barfs on constexpr. A replacement keyword (e.g. "const") can be +// provided, or just leave blank to remove the keyword entirely. +// +// TODO(msvc): Remove this hack once MSVC fully supports constexpr. + +#ifndef __restrict__ +#define __restrict__ __restrict +// TODO(msvc): Would it be better to define a KJ_RESTRICT macro? +#endif + +#pragma warning(disable: 4521 4522) +// This warning complains when there are two copy constructors, one for a const reference and +// one for a non-const reference. It is often quite necessary to do this in wrapper templates, +// therefore this warning is dumb and we disable it. + +#pragma warning(disable: 4458) +// Warns when a parameter name shadows a class member. Unfortunately my code does this a lot, +// since I don't use a special name format for members. + +#else // _MSC_VER +#define KJ_CONSTEXPR(...) constexpr +#endif + +// ======================================================================================= +// Template metaprogramming helpers. + +template struct NoInfer_ { typedef T Type; }; +template using NoInfer = typename NoInfer_::Type; +// Use NoInfer::Type in place of T for a template function parameter to prevent inference of +// the type based on the parameter value. + +template struct RemoveConst_ { typedef T Type; }; +template struct RemoveConst_ { typedef T Type; }; +template using RemoveConst = typename RemoveConst_::Type; + +template struct IsLvalueReference_ { static constexpr bool value = false; }; +template struct IsLvalueReference_ { static constexpr bool value = true; }; +template +inline constexpr bool isLvalueReference() { return IsLvalueReference_::value; } + +template struct Decay_ { typedef T Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template using Decay = typename Decay_::Type; + +template struct EnableIf_; +template <> struct EnableIf_ { typedef void Type; }; +template using EnableIf = typename EnableIf_::Type; +// Use like: +// +// template ()> +// void func(T&& t); + +template struct VoidSfinae_ { using Type = void; }; +template using VoidSfinae = typename VoidSfinae_::Type; +// Note: VoidSfinae is std::void_t from C++17. + +template +T instance() noexcept; +// Like std::declval, but doesn't transform T into an rvalue reference. If you want that, specify +// instance(). + +struct DisallowConstCopy { + // Inherit from this, or declare a member variable of this type, to prevent the class from being + // copyable from a const reference -- instead, it will only be copyable from non-const references. + // This is useful for enforcing transitive constness of contained pointers. + // + // For example, say you have a type T which contains a pointer. T has non-const methods which + // modify the value at that pointer, but T's const methods are designed to allow reading only. + // Unfortunately, if T has a regular copy constructor, someone can simply make a copy of T and + // then use it to modify the pointed-to value. However, if T inherits DisallowConstCopy, then + // callers will only be able to copy non-const instances of T. Ideally, there is some + // parallel type ImmutableT which is like a version of T that only has const methods, and can + // be copied from a const T. + // + // Note that due to C++ rules about implicit copy constructors and assignment operators, any + // type that contains or inherits from a type that disallows const copies will also automatically + // disallow const copies. Hey, cool, that's exactly what we want. + +#if CAPNP_DEBUG_TYPES + // Alas! Declaring a defaulted non-const copy constructor tickles a bug which causes GCC and + // Clang to disagree on ABI, using different calling conventions to pass this type, leading to + // immediate segfaults. See: + // https://bugs.llvm.org/show_bug.cgi?id=23764 + // https://gcc.gnu.org/bugzilla/show_bug.cgi?id=58074 + // + // Because of this, we can't use this technique. We guard it by CAPNP_DEBUG_TYPES so that it + // still applies to the Cap'n Proto developers during internal testing. + + DisallowConstCopy() = default; + DisallowConstCopy(DisallowConstCopy&) = default; + DisallowConstCopy(DisallowConstCopy&&) = default; + DisallowConstCopy& operator=(DisallowConstCopy&) = default; + DisallowConstCopy& operator=(DisallowConstCopy&&) = default; +#endif +}; + +#if _MSC_VER + +#define KJ_CPCAP(obj) obj=::kj::cp(obj) +// TODO(msvc): MSVC refuses to invoke non-const versions of copy constructors in by-value lambda +// captures. Wrap your captured object in this macro to force the compiler to perform a copy. +// Example: +// +// struct Foo: DisallowConstCopy {}; +// Foo foo; +// auto lambda = [KJ_CPCAP(foo)] {}; + +#else + +#define KJ_CPCAP(obj) obj +// Clang and gcc both already perform copy capturing correctly with non-const copy constructors. + +#endif + +template +struct DisallowConstCopyIfNotConst: public DisallowConstCopy { + // Inherit from this when implementing a template that contains a pointer to T and which should + // enforce transitive constness. If T is a const type, this has no effect. Otherwise, it is + // an alias for DisallowConstCopy. +}; + +template +struct DisallowConstCopyIfNotConst {}; + +template struct IsConst_ { static constexpr bool value = false; }; +template struct IsConst_ { static constexpr bool value = true; }; +template constexpr bool isConst() { return IsConst_::value; } + +template struct EnableIfNotConst_ { typedef T Type; }; +template struct EnableIfNotConst_; +template using EnableIfNotConst = typename EnableIfNotConst_::Type; + +template struct EnableIfConst_; +template struct EnableIfConst_ { typedef T Type; }; +template using EnableIfConst = typename EnableIfConst_::Type; + +template struct RemoveConstOrDisable_ { struct Type; }; +template struct RemoveConstOrDisable_ { typedef T Type; }; +template using RemoveConstOrDisable = typename RemoveConstOrDisable_::Type; + +template struct IsReference_ { static constexpr bool value = false; }; +template struct IsReference_ { static constexpr bool value = true; }; +template constexpr bool isReference() { return IsReference_::value; } + +template +struct PropagateConst_ { typedef To Type; }; +template +struct PropagateConst_ { typedef const To Type; }; +template +using PropagateConst = typename PropagateConst_::Type; + +namespace _ { // private + +template +T refIfLvalue(T&&); + +} // namespace _ (private) + +#define KJ_DECLTYPE_REF(exp) decltype(::kj::_::refIfLvalue(exp)) +// Like decltype(exp), but if exp is an lvalue, produces a reference type. +// +// int i; +// decltype(i) i1(i); // i1 has type int. +// KJ_DECLTYPE_REF(i + 1) i2(i + 1); // i2 has type int. +// KJ_DECLTYPE_REF(i) i3(i); // i3 has type int&. +// KJ_DECLTYPE_REF(kj::mv(i)) i4(kj::mv(i)); // i4 has type int. + +template +struct CanConvert_ { + static int sfinae(T); + static bool sfinae(...); +}; + +template +constexpr bool canConvert() { + return sizeof(CanConvert_::sfinae(instance())) == sizeof(int); +} + +#if __GNUC__ && !__clang__ && __GNUC__ < 5 +template +constexpr bool canMemcpy() { + // Returns true if T can be copied using memcpy instead of using the copy constructor or + // assignment operator. + + // GCC 4 does not have __is_trivially_constructible and friends, and there doesn't seem to be + // any reliable alternative. __has_trivial_copy() and __has_trivial_assign() return the right + // thing at one point but later on they changed such that a deleted copy constructor was + // considered "trivial" (apparently technically correct, though useless). So, on GCC 4 we give up + // and assume we can't memcpy() at all, and must explicitly copy-construct everything. + return false; +} +#define KJ_ASSERT_CAN_MEMCPY(T) +#else +template +constexpr bool canMemcpy() { + // Returns true if T can be copied using memcpy instead of using the copy constructor or + // assignment operator. + + return __is_trivially_constructible(T, const T&) && __is_trivially_assignable(T, const T&); +} +#define KJ_ASSERT_CAN_MEMCPY(T) \ + static_assert(kj::canMemcpy(), "this code expects this type to be memcpy()-able"); +#endif + +// ======================================================================================= +// Equivalents to std::move() and std::forward(), since these are very commonly needed and the +// std header pulls in lots of other stuff. +// +// We use abbreviated names mv and fwd because these helpers (especially mv) are so commonly used +// that the cost of typing more letters outweighs the cost of being slightly harder to understand +// when first encountered. + +template constexpr T&& mv(T& t) noexcept { return static_cast(t); } +template constexpr T&& fwd(NoInfer& t) noexcept { return static_cast(t); } + +template constexpr T cp(T& t) noexcept { return t; } +template constexpr T cp(const T& t) noexcept { return t; } +// Useful to force a copy, particularly to pass into a function that expects T&&. + +template struct ChooseType_; +template struct ChooseType_ { typedef T Type; }; +template struct ChooseType_ { typedef T Type; }; +template struct ChooseType_ { typedef U Type; }; + +template +using WiderType = typename ChooseType_= sizeof(U)>::Type; + +template +inline constexpr auto min(T&& a, U&& b) -> WiderType, Decay> { + return a < b ? WiderType, Decay>(a) : WiderType, Decay>(b); +} + +template +inline constexpr auto max(T&& a, U&& b) -> WiderType, Decay> { + return a > b ? WiderType, Decay>(a) : WiderType, Decay>(b); +} + +template +inline constexpr size_t size(T (&arr)[s]) { return s; } +template +inline constexpr size_t size(T&& arr) { return arr.size(); } +// Returns the size of the parameter, whether the parameter is a regular C array or a container +// with a `.size()` method. + +class MaxValue_ { +private: + template + inline constexpr T maxSigned() const { + return (1ull << (sizeof(T) * 8 - 1)) - 1; + } + template + inline constexpr T maxUnsigned() const { + return ~static_cast(0u); + } + +public: +#define _kJ_HANDLE_TYPE(T) \ + inline constexpr operator signed T() const { return MaxValue_::maxSigned < signed T>(); } \ + inline constexpr operator unsigned T() const { return MaxValue_::maxUnsigned(); } + _kJ_HANDLE_TYPE(char) + _kJ_HANDLE_TYPE(short) + _kJ_HANDLE_TYPE(int) + _kJ_HANDLE_TYPE(long) + _kJ_HANDLE_TYPE(long long) +#undef _kJ_HANDLE_TYPE + + inline constexpr operator char() const { + // `char` is different from both `signed char` and `unsigned char`, and may be signed or + // unsigned on different platforms. Ugh. + return char(-1) < 0 ? MaxValue_::maxSigned() + : MaxValue_::maxUnsigned(); + } +}; + +class MinValue_ { +private: + template + inline constexpr T minSigned() const { + return 1ull << (sizeof(T) * 8 - 1); + } + template + inline constexpr T minUnsigned() const { + return 0u; + } + +public: +#define _kJ_HANDLE_TYPE(T) \ + inline constexpr operator signed T() const { return MinValue_::minSigned < signed T>(); } \ + inline constexpr operator unsigned T() const { return MinValue_::minUnsigned(); } + _kJ_HANDLE_TYPE(char) + _kJ_HANDLE_TYPE(short) + _kJ_HANDLE_TYPE(int) + _kJ_HANDLE_TYPE(long) + _kJ_HANDLE_TYPE(long long) +#undef _kJ_HANDLE_TYPE + + inline constexpr operator char() const { + // `char` is different from both `signed char` and `unsigned char`, and may be signed or + // unsigned on different platforms. Ugh. + return char(-1) < 0 ? MinValue_::minSigned() + : MinValue_::minUnsigned(); + } +}; + +static KJ_CONSTEXPR(const) MaxValue_ maxValue = MaxValue_(); +// A special constant which, when cast to an integer type, takes on the maximum possible value of +// that type. This is useful to use as e.g. a parameter to a function because it will be robust +// in the face of changes to the parameter's type. +// +// `char` is not supported, but `signed char` and `unsigned char` are. + +static KJ_CONSTEXPR(const) MinValue_ minValue = MinValue_(); +// A special constant which, when cast to an integer type, takes on the minimum possible value +// of that type. This is useful to use as e.g. a parameter to a function because it will be robust +// in the face of changes to the parameter's type. +// +// `char` is not supported, but `signed char` and `unsigned char` are. + +template +inline bool operator==(T t, MaxValue_) { return t == Decay(maxValue); } +template +inline bool operator==(T t, MinValue_) { return t == Decay(minValue); } + +template +inline constexpr unsigned long long maxValueForBits() { + // Get the maximum integer representable in the given number of bits. + + // 1ull << 64 is unfortunately undefined. + return (bits == 64 ? 0 : (1ull << bits)) - 1; +} + +struct ThrowOverflow { + // Functor which throws an exception complaining about integer overflow. Usually this is used + // with the interfaces in units.h, but is defined here because Cap'n Proto wants to avoid + // including units.h when not using CAPNP_DEBUG_TYPES. + void operator()() const; +}; + +#if __GNUC__ +inline constexpr float inf() { return __builtin_huge_valf(); } +inline constexpr float nan() { return __builtin_nanf(""); } + +#elif _MSC_VER + +// Do what MSVC math.h does +#pragma warning(push) +#pragma warning(disable: 4756) // "overflow in constant arithmetic" +inline constexpr float inf() { return (float)(1e300 * 1e300); } +#pragma warning(pop) + +float nan(); +// Unfortunatley, inf() * 0.0f produces a NaN with the sign bit set, whereas our preferred +// canonical NaN should not have the sign bit set. std::numeric_limits::quiet_NaN() +// returns the correct NaN, but we don't want to #include that here. So, we give up and make +// this out-of-line on MSVC. +// +// TODO(msvc): Can we do better? + +#else +#error "Not sure how to support your compiler." +#endif + +inline constexpr bool isNaN(float f) { return f != f; } +inline constexpr bool isNaN(double f) { return f != f; } + +inline int popCount(unsigned int x) { +#if defined(_MSC_VER) + return __popcnt(x); + // Note: __popcnt returns unsigned int, but the value is clearly guaranteed to fit into an int +#else + return __builtin_popcount(x); +#endif +} + +// ======================================================================================= +// Useful fake containers + +template +class Range { +public: + inline constexpr Range(const T& begin, const T& end): begin_(begin), end_(end) {} + inline explicit constexpr Range(const T& end): begin_(0), end_(end) {} + + class Iterator { + public: + Iterator() = default; + inline Iterator(const T& value): value(value) {} + + inline const T& operator* () const { return value; } + inline const T& operator[](size_t index) const { return value + index; } + inline Iterator& operator++() { ++value; return *this; } + inline Iterator operator++(int) { return Iterator(value++); } + inline Iterator& operator--() { --value; return *this; } + inline Iterator operator--(int) { return Iterator(value--); } + inline Iterator& operator+=(ptrdiff_t amount) { value += amount; return *this; } + inline Iterator& operator-=(ptrdiff_t amount) { value -= amount; return *this; } + inline Iterator operator+ (ptrdiff_t amount) const { return Iterator(value + amount); } + inline Iterator operator- (ptrdiff_t amount) const { return Iterator(value - amount); } + inline ptrdiff_t operator- (const Iterator& other) const { return value - other.value; } + + inline bool operator==(const Iterator& other) const { return value == other.value; } + inline bool operator!=(const Iterator& other) const { return value != other.value; } + inline bool operator<=(const Iterator& other) const { return value <= other.value; } + inline bool operator>=(const Iterator& other) const { return value >= other.value; } + inline bool operator< (const Iterator& other) const { return value < other.value; } + inline bool operator> (const Iterator& other) const { return value > other.value; } + + private: + T value; + }; + + inline Iterator begin() const { return Iterator(begin_); } + inline Iterator end() const { return Iterator(end_); } + + inline auto size() const -> decltype(instance() - instance()) { return end_ - begin_; } + +private: + T begin_; + T end_; +}; + +template +inline constexpr Range, Decay>> range(T begin, U end) { + return Range, Decay>>(begin, end); +} + +template +inline constexpr Range> range(T begin, T end) { return Range>(begin, end); } +// Returns a fake iterable container containing all values of T from `begin` (inclusive) to `end` +// (exclusive). Example: +// +// // Prints 1, 2, 3, 4, 5, 6, 7, 8, 9. +// for (int i: kj::range(1, 10)) { print(i); } + +template +inline constexpr Range> zeroTo(T end) { return Range>(end); } +// Returns a fake iterable container containing all values of T from zero (inclusive) to `end` +// (exclusive). Example: +// +// // Prints 0, 1, 2, 3, 4, 5, 6, 7, 8, 9. +// for (int i: kj::zeroTo(10)) { print(i); } + +template +inline constexpr Range indices(T&& container) { + // Shortcut for iterating over the indices of a container: + // + // for (size_t i: kj::indices(myArray)) { handle(myArray[i]); } + + return range(0, kj::size(container)); +} + +template +class Repeat { +public: + inline constexpr Repeat(const T& value, size_t count): value(value), count(count) {} + + class Iterator { + public: + Iterator() = default; + inline Iterator(const T& value, size_t index): value(value), index(index) {} + + inline const T& operator* () const { return value; } + inline const T& operator[](ptrdiff_t index) const { return value; } + inline Iterator& operator++() { ++index; return *this; } + inline Iterator operator++(int) { return Iterator(value, index++); } + inline Iterator& operator--() { --index; return *this; } + inline Iterator operator--(int) { return Iterator(value, index--); } + inline Iterator& operator+=(ptrdiff_t amount) { index += amount; return *this; } + inline Iterator& operator-=(ptrdiff_t amount) { index -= amount; return *this; } + inline Iterator operator+ (ptrdiff_t amount) const { return Iterator(value, index + amount); } + inline Iterator operator- (ptrdiff_t amount) const { return Iterator(value, index - amount); } + inline ptrdiff_t operator- (const Iterator& other) const { return index - other.index; } + + inline bool operator==(const Iterator& other) const { return index == other.index; } + inline bool operator!=(const Iterator& other) const { return index != other.index; } + inline bool operator<=(const Iterator& other) const { return index <= other.index; } + inline bool operator>=(const Iterator& other) const { return index >= other.index; } + inline bool operator< (const Iterator& other) const { return index < other.index; } + inline bool operator> (const Iterator& other) const { return index > other.index; } + + private: + T value; + size_t index; + }; + + inline Iterator begin() const { return Iterator(value, 0); } + inline Iterator end() const { return Iterator(value, count); } + + inline size_t size() const { return count; } + inline const T& operator[](ptrdiff_t) const { return value; } + +private: + T value; + size_t count; +}; + +template +inline constexpr Repeat> repeat(T&& value, size_t count) { + // Returns a fake iterable which contains `count` repeats of `value`. Useful for e.g. creating + // a bunch of spaces: `kj::repeat(' ', indent * 2)` + + return Repeat>(value, count); +} + +// ======================================================================================= +// Manually invoking constructors and destructors +// +// ctor(x, ...) and dtor(x) invoke x's constructor or destructor, respectively. + +// We want placement new, but we don't want to #include . operator new cannot be defined in +// a namespace, and defining it globally conflicts with the definition in . So we have to +// define a dummy type and an operator new that uses it. + +namespace _ { // private +struct PlacementNew {}; +} // namespace _ (private) +} // namespace kj + +inline void* operator new(size_t, kj::_::PlacementNew, void* __p) noexcept { + return __p; +} + +inline void operator delete(void*, kj::_::PlacementNew, void* __p) noexcept {} + +namespace kj { + +template +inline void ctor(T& location, Params&&... params) { + new (_::PlacementNew(), &location) T(kj::fwd(params)...); +} + +template +inline void dtor(T& location) { + location.~T(); +} + +// ======================================================================================= +// Maybe +// +// Use in cases where you want to indicate that a value may be null. Using Maybe instead of T* +// forces the caller to handle the null case in order to satisfy the compiler, thus reliably +// preventing null pointer dereferences at runtime. +// +// Maybe can be implicitly constructed from T and from nullptr. Additionally, it can be +// implicitly constructed from T*, in which case the pointer is checked for nullness at runtime. +// To read the value of a Maybe, do: +// +// KJ_IF_MAYBE(value, someFuncReturningMaybe()) { +// doSomething(*value); +// } else { +// maybeWasNull(); +// } +// +// KJ_IF_MAYBE's first parameter is a variable name which will be defined within the following +// block. The variable will behave like a (guaranteed non-null) pointer to the Maybe's value, +// though it may or may not actually be a pointer. +// +// Note that Maybe actually just wraps a pointer, whereas Maybe wraps a T and a boolean +// indicating nullness. + +template +class Maybe; + +namespace _ { // private + +template +class NullableValue { + // Class whose interface behaves much like T*, but actually contains an instance of T and a + // boolean flag indicating nullness. + +public: + inline NullableValue(NullableValue&& other) noexcept(noexcept(T(instance()))) + : isSet(other.isSet) { + if (isSet) { + ctor(value, kj::mv(other.value)); + } + } + inline NullableValue(const NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, other.value); + } + } + inline NullableValue(NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, other.value); + } + } + inline ~NullableValue() +#if _MSC_VER + // TODO(msvc): MSVC has a hard time with noexcept specifier expressions that are more complex + // than `true` or `false`. We had a workaround for VS2015, but VS2017 regressed. + noexcept(false) +#else + noexcept(noexcept(instance().~T())) +#endif + { + if (isSet) { + dtor(value); + } + } + + inline T& operator*() & { return value; } + inline const T& operator*() const & { return value; } + inline T&& operator*() && { return kj::mv(value); } + inline const T&& operator*() const && { return kj::mv(value); } + inline T* operator->() { return &value; } + inline const T* operator->() const { return &value; } + inline operator T*() { return isSet ? &value : nullptr; } + inline operator const T*() const { return isSet ? &value : nullptr; } + + template + inline T& emplace(Params&&... params) { + if (isSet) { + isSet = false; + dtor(value); + } + ctor(value, kj::fwd(params)...); + isSet = true; + return value; + } + +private: // internal interface used by friends only + inline NullableValue() noexcept: isSet(false) {} + inline NullableValue(T&& t) noexcept(noexcept(T(instance()))) + : isSet(true) { + ctor(value, kj::mv(t)); + } + inline NullableValue(T& t) + : isSet(true) { + ctor(value, t); + } + inline NullableValue(const T& t) + : isSet(true) { + ctor(value, t); + } + inline NullableValue(const T* t) + : isSet(t != nullptr) { + if (isSet) ctor(value, *t); + } + template + inline NullableValue(NullableValue&& other) noexcept(noexcept(T(instance()))) + : isSet(other.isSet) { + if (isSet) { + ctor(value, kj::mv(other.value)); + } + } + template + inline NullableValue(const NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, other.value); + } + } + template + inline NullableValue(const NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, *other.ptr); + } + } + inline NullableValue(decltype(nullptr)): isSet(false) {} + + inline NullableValue& operator=(NullableValue&& other) { + if (&other != this) { + // Careful about throwing destructors/constructors here. + if (isSet) { + isSet = false; + dtor(value); + } + if (other.isSet) { + ctor(value, kj::mv(other.value)); + isSet = true; + } + } + return *this; + } + + inline NullableValue& operator=(NullableValue& other) { + if (&other != this) { + // Careful about throwing destructors/constructors here. + if (isSet) { + isSet = false; + dtor(value); + } + if (other.isSet) { + ctor(value, other.value); + isSet = true; + } + } + return *this; + } + + inline NullableValue& operator=(const NullableValue& other) { + if (&other != this) { + // Careful about throwing destructors/constructors here. + if (isSet) { + isSet = false; + dtor(value); + } + if (other.isSet) { + ctor(value, other.value); + isSet = true; + } + } + return *this; + } + + inline bool operator==(decltype(nullptr)) const { return !isSet; } + inline bool operator!=(decltype(nullptr)) const { return isSet; } + +private: + bool isSet; + +#if _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4624) +// Warns that the anonymous union has a deleted destructor when T is non-trivial. This warning +// seems broken. +#endif + + union { + T value; + }; + +#if _MSC_VER +#pragma warning(pop) +#endif + + friend class kj::Maybe; + template + friend NullableValue&& readMaybe(Maybe&& maybe); +}; + +template +inline NullableValue&& readMaybe(Maybe&& maybe) { return kj::mv(maybe.ptr); } +template +inline T* readMaybe(Maybe& maybe) { return maybe.ptr; } +template +inline const T* readMaybe(const Maybe& maybe) { return maybe.ptr; } +template +inline T* readMaybe(Maybe&& maybe) { return maybe.ptr; } +template +inline T* readMaybe(const Maybe& maybe) { return maybe.ptr; } + +template +inline T* readMaybe(T* ptr) { return ptr; } +// Allow KJ_IF_MAYBE to work on regular pointers. + +} // namespace _ (private) + +#define KJ_IF_MAYBE(name, exp) if (auto name = ::kj::_::readMaybe(exp)) + +template +class Maybe { + // A T, or nullptr. + + // IF YOU CHANGE THIS CLASS: Note that there is a specialization of it in memory.h. + +public: + Maybe(): ptr(nullptr) {} + Maybe(T&& t) noexcept(noexcept(T(instance()))): ptr(kj::mv(t)) {} + Maybe(T& t): ptr(t) {} + Maybe(const T& t): ptr(t) {} + Maybe(const T* t) noexcept: ptr(t) {} + Maybe(Maybe&& other) noexcept(noexcept(T(instance()))): ptr(kj::mv(other.ptr)) {} + Maybe(const Maybe& other): ptr(other.ptr) {} + Maybe(Maybe& other): ptr(other.ptr) {} + + template + Maybe(Maybe&& other) noexcept(noexcept(T(instance()))) { + KJ_IF_MAYBE(val, kj::mv(other)) { + ptr.emplace(kj::mv(*val)); + } + } + template + Maybe(const Maybe& other) { + KJ_IF_MAYBE(val, other) { + ptr.emplace(*val); + } + } + + Maybe(decltype(nullptr)) noexcept: ptr(nullptr) {} + + template + inline T& emplace(Params&&... params) { + // Replace this Maybe's content with a new value constructed by passing the given parametrs to + // T's constructor. This can be used to initialize a Maybe without copying or even moving a T. + // Returns a reference to the newly-constructed value. + + return ptr.emplace(kj::fwd(params)...); + } + + inline Maybe& operator=(Maybe&& other) { ptr = kj::mv(other.ptr); return *this; } + inline Maybe& operator=(Maybe& other) { ptr = other.ptr; return *this; } + inline Maybe& operator=(const Maybe& other) { ptr = other.ptr; return *this; } + + inline bool operator==(decltype(nullptr)) const { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return ptr != nullptr; } + + T& orDefault(T& defaultValue) { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + const T& orDefault(const T& defaultValue) const { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + + template + auto map(Func&& f) & -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(*ptr); + } + } + + template + auto map(Func&& f) const & -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(*ptr); + } + } + + template + auto map(Func&& f) && -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(*ptr)); + } + } + + template + auto map(Func&& f) const && -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(*ptr)); + } + } + +private: + _::NullableValue ptr; + + template + friend class Maybe; + template + friend _::NullableValue&& _::readMaybe(Maybe&& maybe); + template + friend U* _::readMaybe(Maybe& maybe); + template + friend const U* _::readMaybe(const Maybe& maybe); +}; + +template +class Maybe: public DisallowConstCopyIfNotConst { +public: + Maybe() noexcept: ptr(nullptr) {} + Maybe(T& t) noexcept: ptr(&t) {} + Maybe(T* t) noexcept: ptr(t) {} + + template + inline Maybe(Maybe& other) noexcept: ptr(other.ptr) {} + template + inline Maybe(const Maybe& other) noexcept: ptr(other.ptr) {} + inline Maybe(decltype(nullptr)) noexcept: ptr(nullptr) {} + + inline Maybe& operator=(T& other) noexcept { ptr = &other; return *this; } + inline Maybe& operator=(T* other) noexcept { ptr = other; return *this; } + template + inline Maybe& operator=(Maybe& other) noexcept { ptr = other.ptr; return *this; } + template + inline Maybe& operator=(const Maybe& other) noexcept { ptr = other.ptr; return *this; } + + inline bool operator==(decltype(nullptr)) const { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return ptr != nullptr; } + + T& orDefault(T& defaultValue) { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + const T& orDefault(const T& defaultValue) const { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + + template + auto map(Func&& f) -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(*ptr); + } + } + +private: + T* ptr; + + template + friend class Maybe; + template + friend U* _::readMaybe(Maybe&& maybe); + template + friend U* _::readMaybe(const Maybe& maybe); +}; + +// ======================================================================================= +// ArrayPtr +// +// So common that we put it in common.h rather than array.h. + +template +class ArrayPtr: public DisallowConstCopyIfNotConst { + // A pointer to an array. Includes a size. Like any pointer, it doesn't own the target data, + // and passing by value only copies the pointer, not the target. + +public: + inline constexpr ArrayPtr(): ptr(nullptr), size_(0) {} + inline constexpr ArrayPtr(decltype(nullptr)): ptr(nullptr), size_(0) {} + inline constexpr ArrayPtr(T* ptr, size_t size): ptr(ptr), size_(size) {} + inline constexpr ArrayPtr(T* begin, T* end): ptr(begin), size_(end - begin) {} + inline KJ_CONSTEXPR() ArrayPtr(::std::initializer_list> init) + : ptr(init.begin()), size_(init.size()) {} + + template + inline constexpr ArrayPtr(T (&native)[size]): ptr(native), size_(size) {} + // Construct an ArrayPtr from a native C-style array. + + inline operator ArrayPtr() const { + return ArrayPtr(ptr, size_); + } + inline ArrayPtr asConst() const { + return ArrayPtr(ptr, size_); + } + + inline size_t size() const { return size_; } + inline const T& operator[](size_t index) const { + KJ_IREQUIRE(index < size_, "Out-of-bounds ArrayPtr access."); + return ptr[index]; + } + inline T& operator[](size_t index) { + KJ_IREQUIRE(index < size_, "Out-of-bounds ArrayPtr access."); + return ptr[index]; + } + + inline T* begin() { return ptr; } + inline T* end() { return ptr + size_; } + inline T& front() { return *ptr; } + inline T& back() { return *(ptr + size_ - 1); } + inline const T* begin() const { return ptr; } + inline const T* end() const { return ptr + size_; } + inline const T& front() const { return *ptr; } + inline const T& back() const { return *(ptr + size_ - 1); } + + inline ArrayPtr slice(size_t start, size_t end) const { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds ArrayPtr::slice()."); + return ArrayPtr(ptr + start, end - start); + } + inline ArrayPtr slice(size_t start, size_t end) { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds ArrayPtr::slice()."); + return ArrayPtr(ptr + start, end - start); + } + + inline ArrayPtr> asBytes() const { + // Reinterpret the array as a byte array. This is explicitly legal under C++ aliasing + // rules. + return { reinterpret_cast*>(ptr), size_ * sizeof(T) }; + } + inline ArrayPtr> asChars() const { + // Reinterpret the array as a char array. This is explicitly legal under C++ aliasing + // rules. + return { reinterpret_cast*>(ptr), size_ * sizeof(T) }; + } + + inline bool operator==(decltype(nullptr)) const { return size_ == 0; } + inline bool operator!=(decltype(nullptr)) const { return size_ != 0; } + + inline bool operator==(const ArrayPtr& other) const { + if (size_ != other.size_) return false; + for (size_t i = 0; i < size_; i++) { + if (ptr[i] != other[i]) return false; + } + return true; + } + inline bool operator!=(const ArrayPtr& other) const { return !(*this == other); } + +private: + T* ptr; + size_t size_; +}; + +template +inline constexpr ArrayPtr arrayPtr(T* ptr, size_t size) { + // Use this function to construct ArrayPtrs without writing out the type name. + return ArrayPtr(ptr, size); +} + +template +inline constexpr ArrayPtr arrayPtr(T* begin, T* end) { + // Use this function to construct ArrayPtrs without writing out the type name. + return ArrayPtr(begin, end); +} + +// ======================================================================================= +// Casts + +template +To implicitCast(From&& from) { + // `implicitCast(value)` casts `value` to type `T` only if the conversion is implicit. Useful + // for e.g. resolving ambiguous overloads without sacrificing type-safety. + return kj::fwd(from); +} + +template +Maybe dynamicDowncastIfAvailable(From& from) { + // If RTTI is disabled, always returns nullptr. Otherwise, works like dynamic_cast. Useful + // in situations where dynamic_cast could allow an optimization, but isn't strictly necessary + // for correctness. It is highly recommended that you try to arrange all your dynamic_casts + // this way, as a dynamic_cast that is necessary for correctness implies a flaw in the interface + // design. + + // Force a compile error if To is not a subtype of From. Cross-casting is rare; if it is needed + // we should have a separate cast function like dynamicCrosscastIfAvailable(). + if (false) { + kj::implicitCast(kj::implicitCast(nullptr)); + } + +#if KJ_NO_RTTI + return nullptr; +#else + return dynamic_cast(&from); +#endif +} + +template +To& downcast(From& from) { + // Down-cast a value to a sub-type, asserting that the cast is valid. In opt mode this is a + // static_cast, but in debug mode (when RTTI is enabled) a dynamic_cast will be used to verify + // that the value really has the requested type. + + // Force a compile error if To is not a subtype of From. + if (false) { + kj::implicitCast(kj::implicitCast(nullptr)); + } + +#if !KJ_NO_RTTI + KJ_IREQUIRE(dynamic_cast(&from) != nullptr, "Value cannot be downcast() to requested type."); +#endif + + return static_cast(from); +} + +// ======================================================================================= +// Defer + +namespace _ { // private + +template +class Deferred { +public: + inline Deferred(Func&& func): func(kj::fwd(func)), canceled(false) {} + inline ~Deferred() noexcept(false) { if (!canceled) func(); } + KJ_DISALLOW_COPY(Deferred); + + // This move constructor is usually optimized away by the compiler. + inline Deferred(Deferred&& other): func(kj::mv(other.func)), canceled(false) { + other.canceled = true; + } +private: + Func func; + bool canceled; +}; + +} // namespace _ (private) + +template +_::Deferred defer(Func&& func) { + // Returns an object which will invoke the given functor in its destructor. The object is not + // copyable but is movable with the semantics you'd expect. Since the return type is private, + // you need to assign to an `auto` variable. + // + // The KJ_DEFER macro provides slightly more convenient syntax for the common case where you + // want some code to run at current scope exit. + + return _::Deferred(kj::fwd(func)); +} + +#define KJ_DEFER(code) auto KJ_UNIQUE_NAME(_kjDefer) = ::kj::defer([&](){code;}) +// Run the given code when the function exits, whether by return or exception. + +} // namespace kj + +#endif // KJ_COMMON_H_ diff --git a/phonelibs/capnp-cpp/include/kj/compat/gtest.h b/phonelibs/capnp-cpp/include/kj/compat/gtest.h new file mode 100644 index 00000000000000..016dbdfac322ee --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/compat/gtest.h @@ -0,0 +1,122 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_COMPAT_GTEST_H_ +#define KJ_COMPAT_GTEST_H_ +// This file defines compatibility macros converting Google Test tests into KJ tests. +// +// This is only intended to cover the most common functionality. Many tests will likely need +// additional tweaks. For instance: +// - Using operator<< to print information on failure is not supported. Instead, switch to +// KJ_ASSERT/KJ_EXPECT and pass in stuff to print as additional parameters. +// - Test fixtures are not supported. Allocate your "test fixture" on the stack instead. Do setup +// in the constructor, teardown in the destructor. + +#include "../test.h" + +namespace kj { + +namespace _ { // private + +template +T abs(T value) { return value < 0 ? -value : value; } + +inline bool floatAlmostEqual(float a, float b) { + return a == b || abs(a - b) < (abs(a) + abs(b)) * 1e-5; +} + +inline bool doubleAlmostEqual(double a, double b) { + return a == b || abs(a - b) < (abs(a) + abs(b)) * 1e-12; +} + +} // namespace _ (private) + +#define EXPECT_FALSE(x) KJ_EXPECT(!(x)) +#define EXPECT_TRUE(x) KJ_EXPECT(x) +#define EXPECT_EQ(x, y) KJ_EXPECT((x) == (y), x, y) +#define EXPECT_NE(x, y) KJ_EXPECT((x) != (y), x, y) +#define EXPECT_LE(x, y) KJ_EXPECT((x) <= (y), x, y) +#define EXPECT_GE(x, y) KJ_EXPECT((x) >= (y), x, y) +#define EXPECT_LT(x, y) KJ_EXPECT((x) < (y), x, y) +#define EXPECT_GT(x, y) KJ_EXPECT((x) > (y), x, y) +#define EXPECT_STREQ(x, y) KJ_EXPECT(::strcmp(x, y) == 0, x, y) +#define EXPECT_FLOAT_EQ(x, y) KJ_EXPECT(::kj::_::floatAlmostEqual(y, x), y, x); +#define EXPECT_DOUBLE_EQ(x, y) KJ_EXPECT(::kj::_::doubleAlmostEqual(y, x), y, x); + +#define ASSERT_FALSE(x) KJ_ASSERT(!(x)) +#define ASSERT_TRUE(x) KJ_ASSERT(x) +#define ASSERT_EQ(x, y) KJ_ASSERT((x) == (y), x, y) +#define ASSERT_NE(x, y) KJ_ASSERT((x) != (y), x, y) +#define ASSERT_LE(x, y) KJ_ASSERT((x) <= (y), x, y) +#define ASSERT_GE(x, y) KJ_ASSERT((x) >= (y), x, y) +#define ASSERT_LT(x, y) KJ_ASSERT((x) < (y), x, y) +#define ASSERT_GT(x, y) KJ_ASSERT((x) > (y), x, y) +#define ASSERT_STREQ(x, y) KJ_ASSERT(::strcmp(x, y) == 0, x, y) +#define ASSERT_FLOAT_EQ(x, y) KJ_ASSERT(::kj::_::floatAlmostEqual(y, x), y, x); +#define ASSERT_DOUBLE_EQ(x, y) KJ_ASSERT(::kj::_::doubleAlmostEqual(y, x), y, x); + +class AddFailureAdapter { +public: + AddFailureAdapter(const char* file, int line): file(file), line(line) {} + + ~AddFailureAdapter() { + if (!handled) { + _::Debug::log(file, line, LogSeverity::ERROR, "expectation failed"); + } + } + + template + void operator<<(T&& info) { + handled = true; + _::Debug::log(file, line, LogSeverity::ERROR, "\"expectation failed\", info", + "expectation failed", kj::fwd(info)); + } + +private: + bool handled = false; + const char* file; + int line; +}; + +#define ADD_FAILURE() ::kj::AddFailureAdapter(__FILE__, __LINE__) + +#if KJ_NO_EXCEPTIONS +#define EXPECT_ANY_THROW(code) \ + KJ_EXPECT(::kj::_::expectFatalThrow(nullptr, nullptr, [&]() { code; })) +#else +#define EXPECT_ANY_THROW(code) \ + KJ_EXPECT(::kj::runCatchingExceptions([&]() { code; }) != nullptr) +#endif + +#define EXPECT_NONFATAL_FAILURE(code) \ + EXPECT_TRUE(kj::runCatchingExceptions([&]() { code; }) != nullptr); + +#ifdef KJ_DEBUG +#define EXPECT_DEBUG_ANY_THROW EXPECT_ANY_THROW +#else +#define EXPECT_DEBUG_ANY_THROW(EXP) +#endif + +#define TEST(x, y) KJ_TEST("legacy test: " #x "/" #y) + +} // namespace kj + +#endif // KJ_COMPAT_GTEST_H_ diff --git a/phonelibs/capnp-cpp/include/kj/compat/http.h b/phonelibs/capnp-cpp/include/kj/compat/http.h new file mode 100644 index 00000000000000..8d455cc2588543 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/compat/http.h @@ -0,0 +1,636 @@ +// Copyright (c) 2017 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_COMPAT_HTTP_H_ +#define KJ_COMPAT_HTTP_H_ +// The KJ HTTP client/server library. +// +// This is a simple library which can be used to implement an HTTP client or server. Properties +// of this library include: +// - Uses KJ async framework. +// - Agnostic to transport layer -- you can provide your own. +// - Header parsing is zero-copy -- it results in strings that point directly into the buffer +// received off the wire. +// - Application code which reads and writes headers refers to headers by symbolic names, not by +// string literals, with lookups being array-index-based, not map-based. To make this possible, +// the application announces what headers it cares about in advance, in order to assign numeric +// values to them. +// - Methods are identified by an enum. + +#include +#include +#include +#include +#include + +namespace kj { + +#define KJ_HTTP_FOR_EACH_METHOD(MACRO) \ + MACRO(GET) \ + MACRO(HEAD) \ + MACRO(POST) \ + MACRO(PUT) \ + MACRO(DELETE) \ + MACRO(PATCH) \ + MACRO(PURGE) \ + MACRO(OPTIONS) \ + MACRO(TRACE) \ + /* standard methods */ \ + /* */ \ + /* (CONNECT is intentionally omitted since it is handled specially in HttpHandler) */ \ + \ + MACRO(COPY) \ + MACRO(LOCK) \ + MACRO(MKCOL) \ + MACRO(MOVE) \ + MACRO(PROPFIND) \ + MACRO(PROPPATCH) \ + MACRO(SEARCH) \ + MACRO(UNLOCK) \ + /* WebDAV */ \ + \ + MACRO(REPORT) \ + MACRO(MKACTIVITY) \ + MACRO(CHECKOUT) \ + MACRO(MERGE) \ + /* Subversion */ \ + \ + MACRO(MSEARCH) \ + MACRO(NOTIFY) \ + MACRO(SUBSCRIBE) \ + MACRO(UNSUBSCRIBE) + /* UPnP */ + +#define KJ_HTTP_FOR_EACH_CONNECTION_HEADER(MACRO) \ + MACRO(connection, "Connection") \ + MACRO(contentLength, "Content-Length") \ + MACRO(keepAlive, "Keep-Alive") \ + MACRO(te, "TE") \ + MACRO(trailer, "Trailer") \ + MACRO(transferEncoding, "Transfer-Encoding") \ + MACRO(upgrade, "Upgrade") + +enum class HttpMethod { + // Enum of known HTTP methods. + // + // We use an enum rather than a string to allow for faster parsing and switching and to reduce + // ambiguity. + +#define DECLARE_METHOD(id) id, +KJ_HTTP_FOR_EACH_METHOD(DECLARE_METHOD) +#undef DECLARE_METHOD +}; + +kj::StringPtr KJ_STRINGIFY(HttpMethod method); +kj::Maybe tryParseHttpMethod(kj::StringPtr name); + +class HttpHeaderTable; + +class HttpHeaderId { + // Identifies an HTTP header by numeric ID that indexes into an HttpHeaderTable. + // + // The KJ HTTP API prefers that headers be identified by these IDs for a few reasons: + // - Integer lookups are much more efficient than string lookups. + // - Case-insensitivity is awkward to deal with when const strings are being passed to the lookup + // method. + // - Writing out strings less often means fewer typos. + // + // See HttpHeaderTable for usage hints. + +public: + HttpHeaderId() = default; + + inline bool operator==(const HttpHeaderId& other) const { return id == other.id; } + inline bool operator!=(const HttpHeaderId& other) const { return id != other.id; } + inline bool operator< (const HttpHeaderId& other) const { return id < other.id; } + inline bool operator> (const HttpHeaderId& other) const { return id > other.id; } + inline bool operator<=(const HttpHeaderId& other) const { return id <= other.id; } + inline bool operator>=(const HttpHeaderId& other) const { return id >= other.id; } + + inline size_t hashCode() const { return id; } + + kj::StringPtr toString() const; + + void requireFrom(HttpHeaderTable& table) const; + // In debug mode, throws an exception if the HttpHeaderId is not from the given table. + // + // In opt mode, no-op. + +#define KJ_HTTP_FOR_EACH_BUILTIN_HEADER(MACRO) \ + MACRO(HOST, "Host") \ + MACRO(DATE, "Date") \ + MACRO(LOCATION, "Location") \ + MACRO(CONTENT_TYPE, "Content-Type") + // For convenience, these very-common headers are valid for all HttpHeaderTables. You can refer + // to them like: + // + // HttpHeaderId::HOST + // + // TODO(0.7): Fill this out with more common headers. + +#define DECLARE_HEADER(id, name) \ + static const HttpHeaderId id; + // Declare a constant for each builtin header, e.g.: HttpHeaderId::CONNECTION + + KJ_HTTP_FOR_EACH_BUILTIN_HEADER(DECLARE_HEADER); +#undef DECLARE_HEADER + +private: + HttpHeaderTable* table; + uint id; + + inline explicit constexpr HttpHeaderId(HttpHeaderTable* table, uint id): table(table), id(id) {} + friend class HttpHeaderTable; + friend class HttpHeaders; +}; + +class HttpHeaderTable { + // Construct an HttpHeaderTable to declare which headers you'll be interested in later on, and + // to manufacture IDs for them. + // + // Example: + // + // // Build a header table with the headers we are interested in. + // kj::HttpHeaderTable::Builder builder; + // const HttpHeaderId accept = builder.add("Accept"); + // const HttpHeaderId contentType = builder.add("Content-Type"); + // kj::HttpHeaderTable table(kj::mv(builder)); + // + // // Create an HTTP client. + // auto client = kj::newHttpClient(table, network); + // + // // Get http://example.com. + // HttpHeaders headers(table); + // headers.set(accept, "text/html"); + // auto response = client->send(kj::HttpMethod::GET, "http://example.com", headers) + // .wait(waitScope); + // auto msg = kj::str("Response content type: ", response.headers.get(contentType)); + + struct IdsByNameMap; + +public: + HttpHeaderTable(); + // Constructs a table that only contains the builtin headers. + + class Builder { + public: + Builder(); + HttpHeaderId add(kj::StringPtr name); + Own build(); + + HttpHeaderTable& getFutureTable(); + // Get the still-unbuilt header table. You cannot actually use it until build() has been + // called. + // + // This method exists to help when building a shared header table -- the Builder may be passed + // to several components, each of which will register the headers they need and get a reference + // to the future table. + + private: + kj::Own table; + }; + + KJ_DISALLOW_COPY(HttpHeaderTable); // Can't copy because HttpHeaderId points to the table. + ~HttpHeaderTable() noexcept(false); + + uint idCount(); + // Return the number of IDs in the table. + + kj::Maybe stringToId(kj::StringPtr name); + // Try to find an ID for the given name. The matching is case-insensitive, per the HTTP spec. + // + // Note: if `name` contains characters that aren't allowed in HTTP header names, this may return + // a bogus value rather than null, due to optimizations used in case-insensitive matching. + + kj::StringPtr idToString(HttpHeaderId id); + // Get the canonical string name for the given ID. + +private: + kj::Vector namesById; + kj::Own idsByName; +}; + +class HttpHeaders { + // Represents a set of HTTP headers. + // + // This class guards against basic HTTP header injection attacks: Trying to set a header name or + // value containing a newline, carriage return, or other invalid character will throw an + // exception. + +public: + explicit HttpHeaders(HttpHeaderTable& table); + + KJ_DISALLOW_COPY(HttpHeaders); + HttpHeaders(HttpHeaders&&) = default; + HttpHeaders& operator=(HttpHeaders&&) = default; + + void clear(); + // Clears all contents, as if the object was freshly-allocated. However, calling this rather + // than actually re-allocating the object may avoid re-allocation of internal objects. + + HttpHeaders clone() const; + // Creates a deep clone of the HttpHeaders. The returned object owns all strings it references. + + HttpHeaders cloneShallow() const; + // Creates a shallow clone of the HttpHeaders. The returned object references the same strings + // as the original, owning none of them. + + kj::Maybe get(HttpHeaderId id) const; + // Read a header. + + template + void forEach(Func&& func) const; + // Calls `func(name, value)` for each header in the set -- including headers that aren't mapped + // to IDs in the header table. Both inputs are of type kj::StringPtr. + + void set(HttpHeaderId id, kj::StringPtr value); + void set(HttpHeaderId id, kj::String&& value); + // Sets a header value, overwriting the existing value. + // + // The String&& version is equivalent to calling the other version followed by takeOwnership(). + // + // WARNING: It is the caller's responsibility to ensure that `value` remains valid until the + // HttpHeaders object is destroyed. This allows string literals to be passed without making a + // copy, but complicates the use of dynamic values. Hint: Consider using `takeOwnership()`. + + void add(kj::StringPtr name, kj::StringPtr value); + void add(kj::StringPtr name, kj::String&& value); + void add(kj::String&& name, kj::String&& value); + // Append a header. `name` will be looked up in the header table, but if it's not mapped, the + // header will be added to the list of unmapped headers. + // + // The String&& versions are equivalent to calling the other version followed by takeOwnership(). + // + // WARNING: It is the caller's responsibility to ensure that `name` and `value` remain valid + // until the HttpHeaders object is destroyed. This allows string literals to be passed without + // making a copy, but complicates the use of dynamic values. Hint: Consider using + // `takeOwnership()`. + + void unset(HttpHeaderId id); + // Removes a header. + // + // It's not possible to remove a header by string name because non-indexed headers would take + // O(n) time to remove. Instead, construct a new HttpHeaders object and copy contents. + + void takeOwnership(kj::String&& string); + void takeOwnership(kj::Array&& chars); + void takeOwnership(HttpHeaders&& otherHeaders); + // Takes overship of a string so that it lives until the HttpHeaders object is destroyed. Useful + // when you've passed a dynamic value to set() or add() or parse*(). + + struct ConnectionHeaders { + // These headers govern details of the specific HTTP connection or framing of the content. + // Hence, they are managed internally within the HTTP library, and never appear in an + // HttpHeaders structure. + +#define DECLARE_HEADER(id, name) \ + kj::StringPtr id; + KJ_HTTP_FOR_EACH_CONNECTION_HEADER(DECLARE_HEADER) +#undef DECLARE_HEADER + }; + + struct Request { + HttpMethod method; + kj::StringPtr url; + ConnectionHeaders connectionHeaders; + }; + struct Response { + uint statusCode; + kj::StringPtr statusText; + ConnectionHeaders connectionHeaders; + }; + + kj::Maybe tryParseRequest(kj::ArrayPtr content); + kj::Maybe tryParseResponse(kj::ArrayPtr content); + // Parse an HTTP header blob and add all the headers to this object. + // + // `content` should be all text from the start of the request to the first occurrance of two + // newlines in a row -- including the first of these two newlines, but excluding the second. + // + // The parse is performed with zero copies: The callee clobbers `content` with '\0' characters + // to split it into a bunch of shorter strings. The caller must keep `content` valid until the + // `HttpHeaders` is destroyed, or pass it to `takeOwnership()`. + + kj::String serializeRequest(HttpMethod method, kj::StringPtr url, + const ConnectionHeaders& connectionHeaders) const; + kj::String serializeResponse(uint statusCode, kj::StringPtr statusText, + const ConnectionHeaders& connectionHeaders) const; + // Serialize the headers as a complete request or response blob. The blob uses '\r\n' newlines + // and includes the double-newline to indicate the end of the headers. + + kj::String toString() const; + +private: + HttpHeaderTable* table; + + kj::Array indexedHeaders; + // Size is always table->idCount(). + + struct Header { + kj::StringPtr name; + kj::StringPtr value; + }; + kj::Vector

unindexedHeaders; + + kj::Vector> ownedStrings; + + kj::Maybe addNoCheck(kj::StringPtr name, kj::StringPtr value); + + kj::StringPtr cloneToOwn(kj::StringPtr str); + + kj::String serialize(kj::ArrayPtr word1, + kj::ArrayPtr word2, + kj::ArrayPtr word3, + const ConnectionHeaders& connectionHeaders) const; + + bool parseHeaders(char* ptr, char* end, ConnectionHeaders& connectionHeaders); + + // TODO(perf): Arguably we should store a map, but header sets are never very long + // TODO(perf): We could optimize for common headers by storing them directly as fields. We could + // also add direct accessors for those headers. +}; + +class WebSocket { +public: + WebSocket(kj::Own stream); + // Create a WebSocket wrapping the given I/O stream. + + kj::Promise send(kj::ArrayPtr message); + kj::Promise send(kj::ArrayPtr message); +}; + +class HttpClient { + // Interface to the client end of an HTTP connection. + // + // There are two kinds of clients: + // * Host clients are used when talking to a specific host. The `url` specified in a request + // is actually just a path. (A `Host` header is still required in all requests.) + // * Proxy clients are used when the target could be any arbitrary host on the internet. + // The `url` specified in a request is a full URL including protocol and hostname. + +public: + struct Response { + uint statusCode; + kj::StringPtr statusText; + const HttpHeaders* headers; + kj::Own body; + // `statusText` and `headers` remain valid until `body` is dropped. + }; + + struct Request { + kj::Own body; + // Write the request entity body to this stream, then drop it when done. + // + // May be null for GET and HEAD requests (which have no body) and requests that have + // Content-Length: 0. + + kj::Promise response; + // Promise for the eventual respnose. + }; + + virtual Request request(HttpMethod method, kj::StringPtr url, const HttpHeaders& headers, + kj::Maybe expectedBodySize = nullptr) = 0; + // Perform an HTTP request. + // + // `url` may be a full URL (with protocol and host) or it may be only the path part of the URL, + // depending on whether the client is a proxy client or a host client. + // + // `url` and `headers` need only remain valid until `request()` returns (they can be + // stack-allocated). + // + // `expectedBodySize`, if provided, must be exactly the number of bytes that will be written to + // the body. This will trigger use of the `Content-Length` connection header. Otherwise, + // `Transfer-Encoding: chunked` will be used. + + struct WebSocketResponse { + uint statusCode; + kj::StringPtr statusText; + const HttpHeaders* headers; + kj::OneOf, kj::Own> upstreamOrBody; + // `statusText` and `headers` remain valid until `upstreamOrBody` is dropped. + }; + virtual kj::Promise openWebSocket( + kj::StringPtr url, const HttpHeaders& headers, kj::Own downstream); + // Tries to open a WebSocket. Default implementation calls send() and never returns a WebSocket. + // + // `url` and `headers` are invalidated when the returned promise resolves. + + virtual kj::Promise> connect(kj::String host); + // Handles CONNECT requests. Only relevant for proxy clients. Default implementation throws + // UNIMPLEMENTED. +}; + +class HttpService { + // Interface which HTTP services should implement. + // + // This interface is functionally equivalent to HttpClient, but is intended for applications to + // implement rather than call. The ergonomics and performance of the method signatures are + // optimized for the serving end. + // + // As with clients, there are two kinds of services: + // * Host services are used when talking to a specific host. The `url` specified in a request + // is actually just a path. (A `Host` header is still required in all requests, and the service + // may in fact serve multiple origins via this header.) + // * Proxy services are used when the target could be any arbitrary host on the internet, i.e. to + // implement an HTTP proxy. The `url` specified in a request is a full URL including protocol + // and hostname. + +public: + class Response { + public: + virtual kj::Own send( + uint statusCode, kj::StringPtr statusText, const HttpHeaders& headers, + kj::Maybe expectedBodySize = nullptr) = 0; + // Begin the response. + // + // `statusText` and `headers` need only remain valid until send() returns (they can be + // stack-allocated). + }; + + virtual kj::Promise request( + HttpMethod method, kj::StringPtr url, const HttpHeaders& headers, + kj::AsyncInputStream& requestBody, Response& response) = 0; + // Perform an HTTP request. + // + // `url` may be a full URL (with protocol and host) or it may be only the path part of the URL, + // depending on whether the service is a proxy service or a host service. + // + // `url` and `headers` are invalidated on the first read from `requestBody` or when the returned + // promise resolves, whichever comes first. + + class WebSocketResponse: public Response { + public: + kj::Own startWebSocket( + uint statusCode, kj::StringPtr statusText, const HttpHeaders& headers, + WebSocket& upstream); + // Begin the response. + // + // `statusText` and `headers` need only remain valid until startWebSocket() returns (they can + // be stack-allocated). + }; + + virtual kj::Promise openWebSocket( + kj::StringPtr url, const HttpHeaders& headers, WebSocketResponse& response); + // Tries to open a WebSocket. Default implementation calls request() and never returns a + // WebSocket. + // + // `url` and `headers` are invalidated when the returned promise resolves. + + virtual kj::Promise> connect(kj::String host); + // Handles CONNECT requests. Only relevant for proxy services. Default implementation throws + // UNIMPLEMENTED. +}; + +kj::Own newHttpClient(HttpHeaderTable& responseHeaderTable, kj::Network& network, + kj::Maybe tlsNetwork = nullptr); +// Creates a proxy HttpClient that connects to hosts over the given network. +// +// `responseHeaderTable` is used when parsing HTTP responses. Requests can use any header table. +// +// `tlsNetwork` is required to support HTTPS destination URLs. Otherwise, only HTTP URLs can be +// fetched. + +kj::Own newHttpClient(HttpHeaderTable& responseHeaderTable, kj::AsyncIoStream& stream); +// Creates an HttpClient that speaks over the given pre-established connection. The client may +// be used as a proxy client or a host client depending on whether the peer is operating as +// a proxy. +// +// Note that since this client has only one stream to work with, it will try to pipeline all +// requests on this stream. If one request or response has an I/O failure, all subsequent requests +// fail as well. If the destination server chooses to close the connection after a response, +// subsequent requests will fail. If a response takes a long time, it blocks subsequent responses. +// If a WebSocket is opened successfully, all subsequent requests fail. + +kj::Own newHttpClient(HttpService& service); +kj::Own newHttpService(HttpClient& client); +// Adapts an HttpClient to an HttpService and vice versa. + +struct HttpServerSettings { + kj::Duration headerTimeout = 15 * kj::SECONDS; + // After initial connection open, or after receiving the first byte of a pipelined request, + // the client must send the complete request within this time. + + kj::Duration pipelineTimeout = 5 * kj::SECONDS; + // After one request/response completes, we'll wait up to this long for a pipelined request to + // arrive. +}; + +class HttpServer: private kj::TaskSet::ErrorHandler { + // Class which listens for requests on ports or connections and sends them to an HttpService. + +public: + typedef HttpServerSettings Settings; + + HttpServer(kj::Timer& timer, HttpHeaderTable& requestHeaderTable, HttpService& service, + Settings settings = Settings()); + // Set up an HttpServer that directs incoming connections to the given service. The service + // may be a host service or a proxy service depending on whether you are intending to implement + // an HTTP server or an HTTP proxy. + + kj::Promise drain(); + // Stop accepting new connections or new requests on existing connections. Finish any requests + // that are already executing, then close the connections. Returns once no more requests are + // in-flight. + + kj::Promise listenHttp(kj::ConnectionReceiver& port); + // Accepts HTTP connections on the given port and directs them to the handler. + // + // The returned promise never completes normally. It may throw if port.accept() throws. Dropping + // the returned promise will cause the server to stop listening on the port, but already-open + // connections will continue to be served. Destroy the whole HttpServer to cancel all I/O. + + kj::Promise listenHttp(kj::Own connection); + // Reads HTTP requests from the given connection and directs them to the handler. A successful + // completion of the promise indicates that all requests received on the connection resulted in + // a complete response, and the client closed the connection gracefully or drain() was called. + // The promise throws if an unparseable request is received or if some I/O error occurs. Dropping + // the returned promise will cancel all I/O on the connection and cancel any in-flight requests. + +private: + class Connection; + + kj::Timer& timer; + HttpHeaderTable& requestHeaderTable; + HttpService& service; + Settings settings; + + bool draining = false; + kj::ForkedPromise onDrain; + kj::Own> drainFulfiller; + + uint connectionCount = 0; + kj::Maybe>> zeroConnectionsFulfiller; + + kj::TaskSet tasks; + + HttpServer(kj::Timer& timer, HttpHeaderTable& requestHeaderTable, HttpService& service, + Settings settings, kj::PromiseFulfillerPair paf); + + kj::Promise listenLoop(kj::ConnectionReceiver& port); + + void taskFailed(kj::Exception&& exception) override; +}; + +// ======================================================================================= +// inline implementation + +inline void HttpHeaderId::requireFrom(HttpHeaderTable& table) const { + KJ_IREQUIRE(this->table == nullptr || this->table == &table, + "the provided HttpHeaderId is from the wrong HttpHeaderTable"); +} + +inline kj::Own HttpHeaderTable::Builder::build() { return kj::mv(table); } +inline HttpHeaderTable& HttpHeaderTable::Builder::getFutureTable() { return *table; } + +inline uint HttpHeaderTable::idCount() { return namesById.size(); } + +inline kj::StringPtr HttpHeaderTable::idToString(HttpHeaderId id) { + id.requireFrom(*this); + return namesById[id.id]; +} + +inline kj::Maybe HttpHeaders::get(HttpHeaderId id) const { + id.requireFrom(*table); + auto result = indexedHeaders[id.id]; + return result == nullptr ? kj::Maybe(nullptr) : result; +} + +inline void HttpHeaders::unset(HttpHeaderId id) { + id.requireFrom(*table); + indexedHeaders[id.id] = nullptr; +} + +template +inline void HttpHeaders::forEach(Func&& func) const { + for (auto i: kj::indices(indexedHeaders)) { + if (indexedHeaders[i] != nullptr) { + func(table->idToString(HttpHeaderId(table, i)), indexedHeaders[i]); + } + } + + for (auto& header: unindexedHeaders) { + func(header.name, header.value); + } +} + +} // namespace kj + +#endif // KJ_COMPAT_HTTP_H_ diff --git a/phonelibs/capnp-cpp/include/kj/debug.h b/phonelibs/capnp-cpp/include/kj/debug.h new file mode 100644 index 00000000000000..fff7f98bc02bb5 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/debug.h @@ -0,0 +1,555 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file declares convenient macros for debug logging and error handling. The macros make +// it excessively easy to extract useful context information from code. Example: +// +// KJ_ASSERT(a == b, a, b, "a and b must be the same."); +// +// On failure, this will throw an exception whose description looks like: +// +// myfile.c++:43: bug in code: expected a == b; a = 14; b = 72; a and b must be the same. +// +// As you can see, all arguments after the first provide additional context. +// +// The macros available are: +// +// * `KJ_LOG(severity, ...)`: Just writes a log message, to stderr by default (but you can +// intercept messages by implementing an ExceptionCallback). `severity` is `INFO`, `WARNING`, +// `ERROR`, or `FATAL`. By default, `INFO` logs are not written, but for command-line apps the +// user should be able to pass a flag like `--verbose` to enable them. Other log levels are +// enabled by default. Log messages -- like exceptions -- can be intercepted by registering an +// ExceptionCallback. +// +// * `KJ_DBG(...)`: Like `KJ_LOG`, but intended specifically for temporary log lines added while +// debugging a particular problem. Calls to `KJ_DBG` should always be deleted before committing +// code. It is suggested that you set up a pre-commit hook that checks for this. +// +// * `KJ_ASSERT(condition, ...)`: Throws an exception if `condition` is false, or aborts if +// exceptions are disabled. This macro should be used to check for bugs in the surrounding code +// and its dependencies, but NOT to check for invalid input. The macro may be followed by a +// brace-delimited code block; if so, the block will be executed in the case where the assertion +// fails, before throwing the exception. If control jumps out of the block (e.g. with "break", +// "return", or "goto"), then the error is considered "recoverable" -- in this case, if +// exceptions are disabled, execution will continue normally rather than aborting (but if +// exceptions are enabled, an exception will still be thrown on exiting the block). A "break" +// statement in particular will jump to the code immediately after the block (it does not break +// any surrounding loop or switch). Example: +// +// KJ_ASSERT(value >= 0, "Value cannot be negative.", value) { +// // Assertion failed. Set value to zero to "recover". +// value = 0; +// // Don't abort if exceptions are disabled. Continue normally. +// // (Still throw an exception if they are enabled, though.) +// break; +// } +// // When exceptions are disabled, we'll get here even if the assertion fails. +// // Otherwise, we get here only if the assertion passes. +// +// * `KJ_REQUIRE(condition, ...)`: Like `KJ_ASSERT` but used to check preconditions -- e.g. to +// validate parameters passed from a caller. A failure indicates that the caller is buggy. +// +// * `KJ_SYSCALL(code, ...)`: Executes `code` assuming it makes a system call. A negative result +// is considered an error, with error code reported via `errno`. EINTR is handled by retrying. +// Other errors are handled by throwing an exception. If you need to examine the return code, +// assign it to a variable like so: +// +// int fd; +// KJ_SYSCALL(fd = open(filename, O_RDONLY), filename); +// +// `KJ_SYSCALL` can be followed by a recovery block, just like `KJ_ASSERT`. +// +// * `KJ_NONBLOCKING_SYSCALL(code, ...)`: Like KJ_SYSCALL, but will not throw an exception on +// EAGAIN/EWOULDBLOCK. The calling code should check the syscall's return value to see if it +// indicates an error; in this case, it can assume the error was EAGAIN because any other error +// would have caused an exception to be thrown. +// +// * `KJ_CONTEXT(...)`: Notes additional contextual information relevant to any exceptions thrown +// from within the current scope. That is, until control exits the block in which KJ_CONTEXT() +// is used, if any exception is generated, it will contain the given information in its context +// chain. This is helpful because it can otherwise be very difficult to come up with error +// messages that make sense within low-level helper code. Note that the parameters to +// KJ_CONTEXT() are only evaluated if an exception is thrown. This implies that any variables +// used must remain valid until the end of the scope. +// +// Notes: +// * Do not write expressions with side-effects in the message content part of the macro, as the +// message will not necessarily be evaluated. +// * For every macro `FOO` above except `LOG`, there is also a `FAIL_FOO` macro used to report +// failures that already happened. For the macros that check a boolean condition, `FAIL_FOO` +// omits the first parameter and behaves like it was `false`. `FAIL_SYSCALL` and +// `FAIL_RECOVERABLE_SYSCALL` take a string and an OS error number as the first two parameters. +// The string should be the name of the failed system call. +// * For every macro `FOO` above, there is a `DFOO` version (or `RECOVERABLE_DFOO`) which is only +// executed in debug mode, i.e. when KJ_DEBUG is defined. KJ_DEBUG is defined automatically +// by common.h when compiling without optimization (unless NDEBUG is defined), but you can also +// define it explicitly (e.g. -DKJ_DEBUG). Generally, production builds should NOT use KJ_DEBUG +// as it may enable expensive checks that are unlikely to fail. + +#ifndef KJ_DEBUG_H_ +#define KJ_DEBUG_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "string.h" +#include "exception.h" + +#ifdef ERROR +// This is problematic because windows.h #defines ERROR, which we use in an enum here. +#error "Make sure to to undefine ERROR (or just #include ) before this file" +#endif + +namespace kj { + +#if _MSC_VER +// MSVC does __VA_ARGS__ differently from GCC: +// - A trailing comma before an empty __VA_ARGS__ is removed automatically, whereas GCC wants +// you to request this behavior with "##__VA_ARGS__". +// - If __VA_ARGS__ is passed directly as an argument to another macro, it will be treated as a +// *single* argument rather than an argument list. This can be worked around by wrapping the +// outer macro call in KJ_EXPAND(), which appraently forces __VA_ARGS__ to be expanded before +// the macro is evaluated. I don't understand the C preprocessor. +// - Using "#__VA_ARGS__" to stringify __VA_ARGS__ expands to zero tokens when __VA_ARGS__ is +// empty, rather than expanding to an empty string literal. We can work around by concatenating +// with an empty string literal. + +#define KJ_EXPAND(X) X + +#define KJ_LOG(severity, ...) \ + if (!::kj::_::Debug::shouldLog(::kj::LogSeverity::severity)) {} else \ + ::kj::_::Debug::log(__FILE__, __LINE__, ::kj::LogSeverity::severity, \ + "" #__VA_ARGS__, __VA_ARGS__) + +#define KJ_DBG(...) KJ_EXPAND(KJ_LOG(DBG, __VA_ARGS__)) + +#define KJ_REQUIRE(cond, ...) \ + if (KJ_LIKELY(cond)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #cond, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_REQUIRE(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + nullptr, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, false)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_NONBLOCKING_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, true)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_SYSCALL(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + errorNumber, code, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#if _WIN32 + +#define KJ_WIN32(call, ...) \ + if (::kj::_::Debug::isWin32Success(call)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_WINSOCK(call, ...) \ + if ((call) != SOCKET_ERROR) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_WIN32(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::Win32Error(errorNumber), code, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#endif + +#define KJ_UNIMPLEMENTED(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::UNIMPLEMENTED, \ + nullptr, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +// TODO(msvc): MSVC mis-deduces `ContextImpl` as `ContextImpl` in some edge +// cases, such as inside nested lambdas inside member functions. Wrapping the type in +// `decltype(instance<...>())` helps it deduce the context function's type correctly. +#define KJ_CONTEXT(...) \ + auto KJ_UNIQUE_NAME(_kjContextFunc) = [&]() -> ::kj::_::Debug::Context::Value { \ + return ::kj::_::Debug::Context::Value(__FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription("" #__VA_ARGS__, __VA_ARGS__)); \ + }; \ + decltype(::kj::instance<::kj::_::Debug::ContextImpl>()) \ + KJ_UNIQUE_NAME(_kjContext)(KJ_UNIQUE_NAME(_kjContextFunc)) + +#define KJ_REQUIRE_NONNULL(value, ...) \ + (*[&] { \ + auto _kj_result = ::kj::_::readMaybe(value); \ + if (KJ_UNLIKELY(!_kj_result)) { \ + ::kj::_::Debug::Fault(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #value " != nullptr", "" #__VA_ARGS__, __VA_ARGS__).fatal(); \ + } \ + return _kj_result; \ + }()) + +#define KJ_EXCEPTION(type, ...) \ + ::kj::Exception(::kj::Exception::Type::type, __FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription("" #__VA_ARGS__, __VA_ARGS__)) + +#else + +#define KJ_LOG(severity, ...) \ + if (!::kj::_::Debug::shouldLog(::kj::LogSeverity::severity)) {} else \ + ::kj::_::Debug::log(__FILE__, __LINE__, ::kj::LogSeverity::severity, \ + #__VA_ARGS__, ##__VA_ARGS__) + +#define KJ_DBG(...) KJ_LOG(DBG, ##__VA_ARGS__) + +#define KJ_REQUIRE(cond, ...) \ + if (KJ_LIKELY(cond)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #cond, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_REQUIRE(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + nullptr, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, false)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_NONBLOCKING_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, true)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_SYSCALL(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + errorNumber, code, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#if _WIN32 + +#define KJ_WIN32(call, ...) \ + if (::kj::_::Debug::isWin32Success(call)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_WINSOCK(call, ...) \ + if ((call) != SOCKET_ERROR) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_WIN32(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::Win32Error(errorNumber), code, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#endif + +#define KJ_UNIMPLEMENTED(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::UNIMPLEMENTED, \ + nullptr, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_CONTEXT(...) \ + auto KJ_UNIQUE_NAME(_kjContextFunc) = [&]() -> ::kj::_::Debug::Context::Value { \ + return ::kj::_::Debug::Context::Value(__FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription(#__VA_ARGS__, ##__VA_ARGS__)); \ + }; \ + ::kj::_::Debug::ContextImpl \ + KJ_UNIQUE_NAME(_kjContext)(KJ_UNIQUE_NAME(_kjContextFunc)) + +#define KJ_REQUIRE_NONNULL(value, ...) \ + (*({ \ + auto _kj_result = ::kj::_::readMaybe(value); \ + if (KJ_UNLIKELY(!_kj_result)) { \ + ::kj::_::Debug::Fault(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #value " != nullptr", #__VA_ARGS__, ##__VA_ARGS__).fatal(); \ + } \ + kj::mv(_kj_result); \ + })) + +#define KJ_EXCEPTION(type, ...) \ + ::kj::Exception(::kj::Exception::Type::type, __FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription(#__VA_ARGS__, ##__VA_ARGS__)) + +#endif + +#define KJ_SYSCALL_HANDLE_ERRORS(call) \ + if (int _kjSyscallError = ::kj::_::Debug::syscallError([&](){return (call);}, false)) \ + switch (int error = _kjSyscallError) +// Like KJ_SYSCALL, but doesn't throw. Instead, the block after the macro is a switch block on the +// error. Additionally, the int value `error` is defined within the block. So you can do: +// +// KJ_SYSCALL_HANDLE_ERRORS(foo()) { +// case ENOENT: +// handleNoSuchFile(); +// break; +// case EEXIST: +// handleExists(); +// break; +// default: +// KJ_FAIL_SYSCALL("foo()", error); +// } else { +// handleSuccessCase(); +// } + +#define KJ_ASSERT KJ_REQUIRE +#define KJ_FAIL_ASSERT KJ_FAIL_REQUIRE +#define KJ_ASSERT_NONNULL KJ_REQUIRE_NONNULL +// Use "ASSERT" in place of "REQUIRE" when the problem is local to the immediate surrounding code. +// That is, if the assert ever fails, it indicates that the immediate surrounding code is broken. + +#ifdef KJ_DEBUG +#define KJ_DLOG KJ_LOG +#define KJ_DASSERT KJ_ASSERT +#define KJ_DREQUIRE KJ_REQUIRE +#else +#define KJ_DLOG(...) do {} while (false) +#define KJ_DASSERT(...) do {} while (false) +#define KJ_DREQUIRE(...) do {} while (false) +#endif + +namespace _ { // private + +class Debug { +public: + Debug() = delete; + + typedef LogSeverity Severity; // backwards-compatibility + +#if _WIN32 + struct Win32Error { + // Hack for overloading purposes. + uint number; + inline explicit Win32Error(uint number): number(number) {} + }; +#endif + + static inline bool shouldLog(LogSeverity severity) { return severity >= minSeverity; } + // Returns whether messages of the given severity should be logged. + + static inline void setLogLevel(LogSeverity severity) { minSeverity = severity; } + // Set the minimum message severity which will be logged. + // + // TODO(someday): Expose publicly. + + template + static void log(const char* file, int line, LogSeverity severity, const char* macroArgs, + Params&&... params); + + class Fault { + public: + template + Fault(const char* file, int line, Code code, + const char* condition, const char* macroArgs, Params&&... params); + Fault(const char* file, int line, Exception::Type type, + const char* condition, const char* macroArgs); + Fault(const char* file, int line, int osErrorNumber, + const char* condition, const char* macroArgs); +#if _WIN32 + Fault(const char* file, int line, Win32Error osErrorNumber, + const char* condition, const char* macroArgs); +#endif + ~Fault() noexcept(false); + + KJ_NOINLINE KJ_NORETURN(void fatal()); + // Throw the exception. + + private: + void init(const char* file, int line, Exception::Type type, + const char* condition, const char* macroArgs, ArrayPtr argValues); + void init(const char* file, int line, int osErrorNumber, + const char* condition, const char* macroArgs, ArrayPtr argValues); +#if _WIN32 + void init(const char* file, int line, Win32Error osErrorNumber, + const char* condition, const char* macroArgs, ArrayPtr argValues); +#endif + + Exception* exception; + }; + + class SyscallResult { + public: + inline SyscallResult(int errorNumber): errorNumber(errorNumber) {} + inline operator void*() { return errorNumber == 0 ? this : nullptr; } + inline int getErrorNumber() { return errorNumber; } + + private: + int errorNumber; + }; + + template + static SyscallResult syscall(Call&& call, bool nonblocking); + template + static int syscallError(Call&& call, bool nonblocking); + +#if _WIN32 + static bool isWin32Success(int boolean); + static bool isWin32Success(void* handle); + static Win32Error getWin32Error(); +#endif + + class Context: public ExceptionCallback { + public: + Context(); + KJ_DISALLOW_COPY(Context); + virtual ~Context() noexcept(false); + + struct Value { + const char* file; + int line; + String description; + + inline Value(const char* file, int line, String&& description) + : file(file), line(line), description(mv(description)) {} + }; + + virtual Value evaluate() = 0; + + virtual void onRecoverableException(Exception&& exception) override; + virtual void onFatalException(Exception&& exception) override; + virtual void logMessage(LogSeverity severity, const char* file, int line, int contextDepth, + String&& text) override; + + private: + bool logged; + Maybe value; + + Value ensureInitialized(); + }; + + template + class ContextImpl: public Context { + public: + inline ContextImpl(Func& func): func(func) {} + KJ_DISALLOW_COPY(ContextImpl); + + Value evaluate() override { + return func(); + } + private: + Func& func; + }; + + template + static String makeDescription(const char* macroArgs, Params&&... params); + +private: + static LogSeverity minSeverity; + + static void logInternal(const char* file, int line, LogSeverity severity, const char* macroArgs, + ArrayPtr argValues); + static String makeDescriptionInternal(const char* macroArgs, ArrayPtr argValues); + + static int getOsErrorNumber(bool nonblocking); + // Get the error code of the last error (e.g. from errno). Returns -1 on EINTR. +}; + +template +void Debug::log(const char* file, int line, LogSeverity severity, const char* macroArgs, + Params&&... params) { + String argValues[sizeof...(Params)] = {str(params)...}; + logInternal(file, line, severity, macroArgs, arrayPtr(argValues, sizeof...(Params))); +} + +template <> +inline void Debug::log<>(const char* file, int line, LogSeverity severity, const char* macroArgs) { + logInternal(file, line, severity, macroArgs, nullptr); +} + +template +Debug::Fault::Fault(const char* file, int line, Code code, + const char* condition, const char* macroArgs, Params&&... params) + : exception(nullptr) { + String argValues[sizeof...(Params)] = {str(params)...}; + init(file, line, code, condition, macroArgs, + arrayPtr(argValues, sizeof...(Params))); +} + +inline Debug::Fault::Fault(const char* file, int line, int osErrorNumber, + const char* condition, const char* macroArgs) + : exception(nullptr) { + init(file, line, osErrorNumber, condition, macroArgs, nullptr); +} + +inline Debug::Fault::Fault(const char* file, int line, kj::Exception::Type type, + const char* condition, const char* macroArgs) + : exception(nullptr) { + init(file, line, type, condition, macroArgs, nullptr); +} + +#if _WIN32 +inline Debug::Fault::Fault(const char* file, int line, Win32Error osErrorNumber, + const char* condition, const char* macroArgs) + : exception(nullptr) { + init(file, line, osErrorNumber, condition, macroArgs, nullptr); +} + +inline bool Debug::isWin32Success(int boolean) { + return boolean; +} +inline bool Debug::isWin32Success(void* handle) { + // Assume null and INVALID_HANDLE_VALUE mean failure. + return handle != nullptr && handle != (void*)-1; +} +#endif + +template +Debug::SyscallResult Debug::syscall(Call&& call, bool nonblocking) { + while (call() < 0) { + int errorNum = getOsErrorNumber(nonblocking); + // getOsErrorNumber() returns -1 to indicate EINTR. + // Also, if nonblocking is true, then it returns 0 on EAGAIN, which will then be treated as a + // non-error. + if (errorNum != -1) { + return SyscallResult(errorNum); + } + } + return SyscallResult(0); +} + +template +int Debug::syscallError(Call&& call, bool nonblocking) { + while (call() < 0) { + int errorNum = getOsErrorNumber(nonblocking); + // getOsErrorNumber() returns -1 to indicate EINTR. + // Also, if nonblocking is true, then it returns 0 on EAGAIN, which will then be treated as a + // non-error. + if (errorNum != -1) { + return errorNum; + } + } + return 0; +} + +template +String Debug::makeDescription(const char* macroArgs, Params&&... params) { + String argValues[sizeof...(Params)] = {str(params)...}; + return makeDescriptionInternal(macroArgs, arrayPtr(argValues, sizeof...(Params))); +} + +template <> +inline String Debug::makeDescription<>(const char* macroArgs) { + return makeDescriptionInternal(macroArgs, nullptr); +} + +} // namespace _ (private) +} // namespace kj + +#endif // KJ_DEBUG_H_ diff --git a/phonelibs/capnp-cpp/include/kj/exception.h b/phonelibs/capnp-cpp/include/kj/exception.h new file mode 100644 index 00000000000000..f6c0b2daa61eeb --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/exception.h @@ -0,0 +1,363 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_EXCEPTION_H_ +#define KJ_EXCEPTION_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" +#include "array.h" +#include "string.h" + +namespace kj { + +class ExceptionImpl; + +class Exception { + // Exception thrown in case of fatal errors. + // + // Actually, a subclass of this which also implements std::exception will be thrown, but we hide + // that fact from the interface to avoid #including . + +public: + enum class Type { + // What kind of failure? + + FAILED = 0, + // Something went wrong. This is the usual error type. KJ_ASSERT and KJ_REQUIRE throw this + // error type. + + OVERLOADED = 1, + // The call failed because of a temporary lack of resources. This could be space resources + // (out of memory, out of disk space) or time resources (request queue overflow, operation + // timed out). + // + // The operation might work if tried again, but it should NOT be repeated immediately as this + // may simply exacerbate the problem. + + DISCONNECTED = 2, + // The call required communication over a connection that has been lost. The callee will need + // to re-establish connections and try again. + + UNIMPLEMENTED = 3 + // The requested method is not implemented. The caller may wish to revert to a fallback + // approach based on other methods. + + // IF YOU ADD A NEW VALUE: + // - Update the stringifier. + // - Update Cap'n Proto's RPC protocol's Exception.Type enum. + }; + + Exception(Type type, const char* file, int line, String description = nullptr) noexcept; + Exception(Type type, String file, int line, String description = nullptr) noexcept; + Exception(const Exception& other) noexcept; + Exception(Exception&& other) = default; + ~Exception() noexcept; + + const char* getFile() const { return file; } + int getLine() const { return line; } + Type getType() const { return type; } + StringPtr getDescription() const { return description; } + ArrayPtr getStackTrace() const { return arrayPtr(trace, traceCount); } + + struct Context { + // Describes a bit about what was going on when the exception was thrown. + + const char* file; + int line; + String description; + Maybe> next; + + Context(const char* file, int line, String&& description, Maybe>&& next) + : file(file), line(line), description(mv(description)), next(mv(next)) {} + Context(const Context& other) noexcept; + }; + + inline Maybe getContext() const { + KJ_IF_MAYBE(c, context) { + return **c; + } else { + return nullptr; + } + } + + void wrapContext(const char* file, int line, String&& description); + // Wraps the context in a new node. This becomes the head node returned by getContext() -- it + // is expected that contexts will be added in reverse order as the exception passes up the + // callback stack. + + KJ_NOINLINE void extendTrace(uint ignoreCount); + // Append the current stack trace to the exception's trace, ignoring the first `ignoreCount` + // frames (see `getStackTrace()` for discussion of `ignoreCount`). + + KJ_NOINLINE void truncateCommonTrace(); + // Remove the part of the stack trace which the exception shares with the caller of this method. + // This is used by the async library to remove the async infrastructure from the stack trace + // before replacing it with the async trace. + + void addTrace(void* ptr); + // Append the given pointer to the backtrace, if it is not already full. This is used by the + // async library to trace through the promise chain that led to the exception. + +private: + String ownFile; + const char* file; + int line; + Type type; + String description; + Maybe> context; + void* trace[32]; + uint traceCount; + + friend class ExceptionImpl; +}; + +StringPtr KJ_STRINGIFY(Exception::Type type); +String KJ_STRINGIFY(const Exception& e); + +// ======================================================================================= + +enum class LogSeverity { + INFO, // Information describing what the code is up to, which users may request to see + // with a flag like `--verbose`. Does not indicate a problem. Not printed by + // default; you must call setLogLevel(INFO) to enable. + WARNING, // A problem was detected but execution can continue with correct output. + ERROR, // Something is wrong, but execution can continue with garbage output. + FATAL, // Something went wrong, and execution cannot continue. + DBG // Temporary debug logging. See KJ_DBG. + + // Make sure to update the stringifier if you add a new severity level. +}; + +StringPtr KJ_STRINGIFY(LogSeverity severity); + +class ExceptionCallback { + // If you don't like C++ exceptions, you may implement and register an ExceptionCallback in order + // to perform your own exception handling. For example, a reasonable thing to do is to have + // onRecoverableException() set a flag indicating that an error occurred, and then check for that + // flag just before writing to storage and/or returning results to the user. If the flag is set, + // discard whatever you have and return an error instead. + // + // ExceptionCallbacks must always be allocated on the stack. When an exception is thrown, the + // newest ExceptionCallback on the calling thread's stack is called. The default implementation + // of each method calls the next-oldest ExceptionCallback for that thread. Thus the callbacks + // behave a lot like try/catch blocks, except that they are called before any stack unwinding + // occurs. + +public: + ExceptionCallback(); + KJ_DISALLOW_COPY(ExceptionCallback); + virtual ~ExceptionCallback() noexcept(false); + + virtual void onRecoverableException(Exception&& exception); + // Called when an exception has been raised, but the calling code has the ability to continue by + // producing garbage output. This method _should_ throw the exception, but is allowed to simply + // return if garbage output is acceptable. + // + // The global default implementation throws an exception unless the library was compiled with + // -fno-exceptions, in which case it logs an error and returns. + + virtual void onFatalException(Exception&& exception); + // Called when an exception has been raised and the calling code cannot continue. If this method + // returns normally, abort() will be called. The method must throw the exception to avoid + // aborting. + // + // The global default implementation throws an exception unless the library was compiled with + // -fno-exceptions, in which case it logs an error and returns. + + virtual void logMessage(LogSeverity severity, const char* file, int line, int contextDepth, + String&& text); + // Called when something wants to log some debug text. `contextDepth` indicates how many levels + // of context the message passed through; it may make sense to indent the message accordingly. + // + // The global default implementation writes the text to stderr. + + enum class StackTraceMode { + FULL, + // Stringifying a stack trace will attempt to determine source file and line numbers. This may + // be expensive. For example, on Linux, this shells out to `addr2line`. + // + // This is the default in debug builds. + + ADDRESS_ONLY, + // Stringifying a stack trace will only generate a list of code addresses. + // + // This is the default in release builds. + + NONE + // Generating a stack trace will always return an empty array. + // + // This avoids ever unwinding the stack. On Windows in particular, the stack unwinding library + // has been observed to be pretty slow, so exception-heavy code might benefit significantly + // from this setting. (But exceptions should be rare...) + }; + + virtual StackTraceMode stackTraceMode(); + // Returns the current preferred stack trace mode. + +protected: + ExceptionCallback& next; + +private: + ExceptionCallback(ExceptionCallback& next); + + class RootExceptionCallback; + friend ExceptionCallback& getExceptionCallback(); +}; + +ExceptionCallback& getExceptionCallback(); +// Returns the current exception callback. + +KJ_NOINLINE KJ_NORETURN(void throwFatalException(kj::Exception&& exception, uint ignoreCount = 0)); +// Invoke the exception callback to throw the given fatal exception. If the exception callback +// returns, abort. + +KJ_NOINLINE void throwRecoverableException(kj::Exception&& exception, uint ignoreCount = 0); +// Invoke the exception callback to throw the given recoverable exception. If the exception +// callback returns, return normally. + +// ======================================================================================= + +namespace _ { class Runnable; } + +template +Maybe runCatchingExceptions(Func&& func) noexcept; +// Executes the given function (usually, a lambda returning nothing) catching any exceptions that +// are thrown. Returns the Exception if there was one, or null if the operation completed normally. +// Non-KJ exceptions will be wrapped. +// +// If exception are disabled (e.g. with -fno-exceptions), this will still detect whether any +// recoverable exceptions occurred while running the function and will return those. + +class UnwindDetector { + // Utility for detecting when a destructor is called due to unwind. Useful for: + // - Avoiding throwing exceptions in this case, which would terminate the program. + // - Detecting whether to commit or roll back a transaction. + // + // To use this class, either inherit privately from it or declare it as a member. The detector + // works by comparing the exception state against that when the constructor was called, so for + // an object that was actually constructed during exception unwind, it will behave as if no + // unwind is taking place. This is usually the desired behavior. + +public: + UnwindDetector(); + + bool isUnwinding() const; + // Returns true if the current thread is in a stack unwind that it wasn't in at the time the + // object was constructed. + + template + void catchExceptionsIfUnwinding(Func&& func) const; + // Runs the given function (e.g., a lambda). If isUnwinding() is true, any exceptions are + // caught and treated as secondary faults, meaning they are considered to be side-effects of the + // exception that is unwinding the stack. Otherwise, exceptions are passed through normally. + +private: + uint uncaughtCount; + + void catchExceptionsAsSecondaryFaults(_::Runnable& runnable) const; +}; + +namespace _ { // private + +class Runnable { +public: + virtual void run() = 0; +}; + +template +class RunnableImpl: public Runnable { +public: + RunnableImpl(Func&& func): func(kj::mv(func)) {} + void run() override { + func(); + } +private: + Func func; +}; + +Maybe runCatchingExceptions(Runnable& runnable) noexcept; + +} // namespace _ (private) + +template +Maybe runCatchingExceptions(Func&& func) noexcept { + _::RunnableImpl> runnable(kj::fwd(func)); + return _::runCatchingExceptions(runnable); +} + +template +void UnwindDetector::catchExceptionsIfUnwinding(Func&& func) const { + if (isUnwinding()) { + _::RunnableImpl> runnable(kj::fwd(func)); + catchExceptionsAsSecondaryFaults(runnable); + } else { + func(); + } +} + +#define KJ_ON_SCOPE_SUCCESS(code) \ + ::kj::UnwindDetector KJ_UNIQUE_NAME(_kjUnwindDetector); \ + KJ_DEFER(if (!KJ_UNIQUE_NAME(_kjUnwindDetector).isUnwinding()) { code; }) +// Runs `code` if the current scope is exited normally (not due to an exception). + +#define KJ_ON_SCOPE_FAILURE(code) \ + ::kj::UnwindDetector KJ_UNIQUE_NAME(_kjUnwindDetector); \ + KJ_DEFER(if (KJ_UNIQUE_NAME(_kjUnwindDetector).isUnwinding()) { code; }) +// Runs `code` if the current scope is exited due to an exception. + +// ======================================================================================= + +KJ_NOINLINE ArrayPtr getStackTrace(ArrayPtr space, uint ignoreCount); +// Attempt to get the current stack trace, returning a list of pointers to instructions. The +// returned array is a slice of `space`. Provide a larger `space` to get a deeper stack trace. +// If the platform doesn't support stack traces, returns an empty array. +// +// `ignoreCount` items will be truncated from the front of the trace. This is useful for chopping +// off a prefix of the trace that is uninteresting to the developer because it's just locations +// inside the debug infrastructure that is requesting the trace. Be careful to mark functions as +// KJ_NOINLINE if you intend to count them in `ignoreCount`. Note that, unfortunately, the +// ignored entries will still waste space in the `space` array (and the returned array's `begin()` +// is never exactly equal to `space.begin()` due to this effect, even if `ignoreCount` is zero +// since `getStackTrace()` needs to ignore its own internal frames). + +String stringifyStackTrace(ArrayPtr); +// Convert the stack trace to a string with file names and line numbers. This may involve executing +// suprocesses. + +String getStackTrace(); +// Get a stack trace right now and stringify it. Useful for debugging. + +void printStackTraceOnCrash(); +// Registers signal handlers on common "crash" signals like SIGSEGV that will (attempt to) print +// a stack trace. You should call this as early as possible on program startup. Programs using +// KJ_MAIN get this automatically. + +kj::StringPtr trimSourceFilename(kj::StringPtr filename); +// Given a source code file name, trim off noisy prefixes like "src/" or +// "/ekam-provider/canonical/". + +} // namespace kj + +#endif // KJ_EXCEPTION_H_ diff --git a/phonelibs/capnp-cpp/include/kj/function.h b/phonelibs/capnp-cpp/include/kj/function.h new file mode 100644 index 00000000000000..ba6601b560cd8e --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/function.h @@ -0,0 +1,277 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_FUNCTION_H_ +#define KJ_FUNCTION_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" + +namespace kj { + +template +class Function; +// Function wrapper using virtual-based polymorphism. Use this when template polymorphism is +// not possible. You can, for example, accept a Function as a parameter: +// +// void setFilter(Function filter); +// +// The caller of `setFilter()` may then pass any callable object as the parameter. The callable +// object does not have to have the exact signature specified, just one that is "compatible" -- +// i.e. the return type is covariant and the parameters are contravariant. +// +// Unlike `std::function`, `kj::Function`s are movable but not copyable, just like `kj::Own`. This +// is to avoid unexpected heap allocation or slow atomic reference counting. +// +// When a `Function` is constructed from an lvalue, it captures only a reference to the value. +// When constructed from an rvalue, it invokes the value's move constructor. So, for example: +// +// struct AddN { +// int n; +// int operator(int i) { return i + n; } +// } +// +// Function f1 = AddN{2}; +// // f1 owns an instance of AddN. It may safely be moved out +// // of the local scope. +// +// AddN adder(2); +// Function f2 = adder; +// // f2 contains a reference to `adder`. Thus, it becomes invalid +// // when `adder` goes out-of-scope. +// +// AddN adder2(2); +// Function f3 = kj::mv(adder2); +// // f3 owns an insatnce of AddN moved from `adder2`. f3 may safely +// // be moved out of the local scope. +// +// Additionally, a Function may be bound to a class method using KJ_BIND_METHOD(object, methodName). +// For example: +// +// class Printer { +// public: +// void print(int i); +// void print(kj::StringPtr s); +// }; +// +// Printer p; +// +// Function intPrinter = KJ_BIND_METHOD(p, print); +// // Will call Printer::print(int). +// +// Function strPrinter = KJ_BIND_METHOD(p, print); +// // Will call Printer::print(kj::StringPtr). +// +// Notice how KJ_BIND_METHOD is able to figure out which overload to use depending on the kind of +// Function it is binding to. + +template +class ConstFunction; +// Like Function, but wraps a "const" (i.e. thread-safe) call. + +template +class Function { +public: + template + inline Function(F&& f): impl(heap>(kj::fwd(f))) {} + Function() = default; + + // Make sure people don't accidentally end up wrapping a reference when they meant to return + // a function. + KJ_DISALLOW_COPY(Function); + Function(Function&) = delete; + Function& operator=(Function&) = delete; + template Function(const Function&) = delete; + template Function& operator=(const Function&) = delete; + template Function(const ConstFunction&) = delete; + template Function& operator=(const ConstFunction&) = delete; + Function(Function&&) = default; + Function& operator=(Function&&) = default; + + inline Return operator()(Params... params) { + return (*impl)(kj::fwd(params)...); + } + + Function reference() { + // Forms a new Function of the same type that delegates to this Function by reference. + // Therefore, this Function must outlive the returned Function, but otherwise they behave + // exactly the same. + + return *impl; + } + +private: + class Iface { + public: + virtual Return operator()(Params... params) = 0; + }; + + template + class Impl final: public Iface { + public: + explicit Impl(F&& f): f(kj::fwd(f)) {} + + Return operator()(Params... params) override { + return f(kj::fwd(params)...); + } + + private: + F f; + }; + + Own impl; +}; + +template +class ConstFunction { +public: + template + inline ConstFunction(F&& f): impl(heap>(kj::fwd(f))) {} + ConstFunction() = default; + + // Make sure people don't accidentally end up wrapping a reference when they meant to return + // a function. + KJ_DISALLOW_COPY(ConstFunction); + ConstFunction(ConstFunction&) = delete; + ConstFunction& operator=(ConstFunction&) = delete; + template ConstFunction(const ConstFunction&) = delete; + template ConstFunction& operator=(const ConstFunction&) = delete; + template ConstFunction(const Function&) = delete; + template ConstFunction& operator=(const Function&) = delete; + ConstFunction(ConstFunction&&) = default; + ConstFunction& operator=(ConstFunction&&) = default; + + inline Return operator()(Params... params) const { + return (*impl)(kj::fwd(params)...); + } + + ConstFunction reference() const { + // Forms a new ConstFunction of the same type that delegates to this ConstFunction by reference. + // Therefore, this ConstFunction must outlive the returned ConstFunction, but otherwise they + // behave exactly the same. + + return *impl; + } + +private: + class Iface { + public: + virtual Return operator()(Params... params) const = 0; + }; + + template + class Impl final: public Iface { + public: + explicit Impl(F&& f): f(kj::fwd(f)) {} + + Return operator()(Params... params) const override { + return f(kj::fwd(params)...); + } + + private: + F f; + }; + + Own impl; +}; + +#if 1 + +namespace _ { // private + +template +class BoundMethod; + +template ::*method)(Params...)> +class BoundMethod::*)(Params...), method> { +public: + BoundMethod(T&& t): t(kj::fwd(t)) {} + + Return operator()(Params&&... params) { + return (t.*method)(kj::fwd(params)...); + } + +private: + T t; +}; + +template ::*method)(Params...) const> +class BoundMethod::*)(Params...) const, method> { +public: + BoundMethod(T&& t): t(kj::fwd(t)) {} + + Return operator()(Params&&... params) const { + return (t.*method)(kj::fwd(params)...); + } + +private: + T t; +}; + +} // namespace _ (private) + +#define KJ_BIND_METHOD(obj, method) \ + ::kj::_::BoundMethod::method), \ + &::kj::Decay::method>(obj) +// Macro that produces a functor object which forwards to the method `obj.name`. If `obj` is an +// lvalue, the functor will hold a reference to it. If `obj` is an rvalue, the functor will +// contain a copy (by move) of it. +// +// The current implementation requires that the method is not overloaded. +// +// TODO(someday): C++14's generic lambdas may be able to simplify this code considerably, and +// probably make it work with overloaded methods. + +#else +// Here's a better implementation of the above that doesn't work with GCC (but does with Clang) +// because it uses a local class with a template method. Sigh. This implementation supports +// overloaded methods. + +#define KJ_BIND_METHOD(obj, method) \ + ({ \ + typedef KJ_DECLTYPE_REF(obj) T; \ + class F { \ + public: \ + inline F(T&& t): t(::kj::fwd(t)) {} \ + template \ + auto operator()(Params&&... params) \ + -> decltype(::kj::instance().method(::kj::fwd(params)...)) { \ + return t.method(::kj::fwd(params)...); \ + } \ + private: \ + T t; \ + }; \ + (F(obj)); \ + }) +// Macro that produces a functor object which forwards to the method `obj.name`. If `obj` is an +// lvalue, the functor will hold a reference to it. If `obj` is an rvalue, the functor will +// contain a copy (by move) of it. + +#endif + +} // namespace kj + +#endif // KJ_FUNCTION_H_ diff --git a/phonelibs/capnp-cpp/include/kj/io.h b/phonelibs/capnp-cpp/include/kj/io.h new file mode 100644 index 00000000000000..f5c03bfe7b8a39 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/io.h @@ -0,0 +1,419 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_IO_H_ +#define KJ_IO_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include +#include "common.h" +#include "array.h" +#include "exception.h" + +namespace kj { + +// ======================================================================================= +// Abstract interfaces + +class InputStream { +public: + virtual ~InputStream() noexcept(false); + + size_t read(void* buffer, size_t minBytes, size_t maxBytes); + // Reads at least minBytes and at most maxBytes, copying them into the given buffer. Returns + // the size read. Throws an exception on errors. Implemented in terms of tryRead(). + // + // maxBytes is the number of bytes the caller really wants, but minBytes is the minimum amount + // needed by the caller before it can start doing useful processing. If the stream returns less + // than maxBytes, the caller will usually call read() again later to get the rest. Returning + // less than maxBytes is useful when it makes sense for the caller to parallelize processing + // with I/O. + // + // Never blocks if minBytes is zero. If minBytes is zero and maxBytes is non-zero, this may + // attempt a non-blocking read or may just return zero. To force a read, use a non-zero minBytes. + // To detect EOF without throwing an exception, use tryRead(). + // + // If the InputStream can't produce minBytes, it MUST throw an exception, as the caller is not + // expected to understand how to deal with partial reads. + + virtual size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) = 0; + // Like read(), but may return fewer than minBytes on EOF. + + inline void read(void* buffer, size_t bytes) { read(buffer, bytes, bytes); } + // Convenience method for reading an exact number of bytes. + + virtual void skip(size_t bytes); + // Skips past the given number of bytes, discarding them. The default implementation read()s + // into a scratch buffer. +}; + +class OutputStream { +public: + virtual ~OutputStream() noexcept(false); + + virtual void write(const void* buffer, size_t size) = 0; + // Always writes the full size. Throws exception on error. + + virtual void write(ArrayPtr> pieces); + // Equivalent to write()ing each byte array in sequence, which is what the default implementation + // does. Override if you can do something better, e.g. use writev() to do the write in a single + // syscall. +}; + +class BufferedInputStream: public InputStream { + // An input stream which buffers some bytes in memory to reduce system call overhead. + // - OR - + // An input stream that actually reads from some in-memory data structure and wants to give its + // caller a direct pointer to that memory to potentially avoid a copy. + +public: + virtual ~BufferedInputStream() noexcept(false); + + ArrayPtr getReadBuffer(); + // Get a direct pointer into the read buffer, which contains the next bytes in the input. If the + // caller consumes any bytes, it should then call skip() to indicate this. This always returns a + // non-empty buffer or throws an exception. Implemented in terms of tryGetReadBuffer(). + + virtual ArrayPtr tryGetReadBuffer() = 0; + // Like getReadBuffer() but may return an empty buffer on EOF. +}; + +class BufferedOutputStream: public OutputStream { + // An output stream which buffers some bytes in memory to reduce system call overhead. + // - OR - + // An output stream that actually writes into some in-memory data structure and wants to give its + // caller a direct pointer to that memory to potentially avoid a copy. + +public: + virtual ~BufferedOutputStream() noexcept(false); + + virtual ArrayPtr getWriteBuffer() = 0; + // Get a direct pointer into the write buffer. The caller may choose to fill in some prefix of + // this buffer and then pass it to write(), in which case write() may avoid a copy. It is + // incorrect to pass to write any slice of this buffer which is not a prefix. +}; + +// ======================================================================================= +// Buffered streams implemented as wrappers around regular streams + +class BufferedInputStreamWrapper: public BufferedInputStream { + // Implements BufferedInputStream in terms of an InputStream. + // + // Note that the underlying stream's position is unpredictable once the wrapper is destroyed, + // unless the entire stream was consumed. To read a predictable number of bytes in a buffered + // way without going over, you'd need this wrapper to wrap some other wrapper which itself + // implements an artificial EOF at the desired point. Such a stream should be trivial to write + // but is not provided by the library at this time. + +public: + explicit BufferedInputStreamWrapper(InputStream& inner, ArrayPtr buffer = nullptr); + // Creates a buffered stream wrapping the given non-buffered stream. No guarantee is made about + // the position of the inner stream after a buffered wrapper has been created unless the entire + // input is read. + // + // If the second parameter is non-null, the stream uses the given buffer instead of allocating + // its own. This may improve performance if the buffer can be reused. + + KJ_DISALLOW_COPY(BufferedInputStreamWrapper); + ~BufferedInputStreamWrapper() noexcept(false); + + // implements BufferedInputStream ---------------------------------- + ArrayPtr tryGetReadBuffer() override; + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + void skip(size_t bytes) override; + +private: + InputStream& inner; + Array ownedBuffer; + ArrayPtr buffer; + ArrayPtr bufferAvailable; +}; + +class BufferedOutputStreamWrapper: public BufferedOutputStream { + // Implements BufferedOutputStream in terms of an OutputStream. Note that writes to the + // underlying stream may be delayed until flush() is called or the wrapper is destroyed. + +public: + explicit BufferedOutputStreamWrapper(OutputStream& inner, ArrayPtr buffer = nullptr); + // Creates a buffered stream wrapping the given non-buffered stream. + // + // If the second parameter is non-null, the stream uses the given buffer instead of allocating + // its own. This may improve performance if the buffer can be reused. + + KJ_DISALLOW_COPY(BufferedOutputStreamWrapper); + ~BufferedOutputStreamWrapper() noexcept(false); + + void flush(); + // Force the wrapper to write any remaining bytes in its buffer to the inner stream. Note that + // this only flushes this object's buffer; this object has no idea how to flush any other buffers + // that may be present in the underlying stream. + + // implements BufferedOutputStream --------------------------------- + ArrayPtr getWriteBuffer() override; + void write(const void* buffer, size_t size) override; + +private: + OutputStream& inner; + Array ownedBuffer; + ArrayPtr buffer; + byte* bufferPos; + UnwindDetector unwindDetector; +}; + +// ======================================================================================= +// Array I/O + +class ArrayInputStream: public BufferedInputStream { +public: + explicit ArrayInputStream(ArrayPtr array); + KJ_DISALLOW_COPY(ArrayInputStream); + ~ArrayInputStream() noexcept(false); + + // implements BufferedInputStream ---------------------------------- + ArrayPtr tryGetReadBuffer() override; + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + void skip(size_t bytes) override; + +private: + ArrayPtr array; +}; + +class ArrayOutputStream: public BufferedOutputStream { +public: + explicit ArrayOutputStream(ArrayPtr array); + KJ_DISALLOW_COPY(ArrayOutputStream); + ~ArrayOutputStream() noexcept(false); + + ArrayPtr getArray() { + // Get the portion of the array which has been filled in. + return arrayPtr(array.begin(), fillPos); + } + + // implements BufferedInputStream ---------------------------------- + ArrayPtr getWriteBuffer() override; + void write(const void* buffer, size_t size) override; + +private: + ArrayPtr array; + byte* fillPos; +}; + +class VectorOutputStream: public BufferedOutputStream { +public: + explicit VectorOutputStream(size_t initialCapacity = 4096); + KJ_DISALLOW_COPY(VectorOutputStream); + ~VectorOutputStream() noexcept(false); + + ArrayPtr getArray() { + // Get the portion of the array which has been filled in. + return arrayPtr(vector.begin(), fillPos); + } + + // implements BufferedInputStream ---------------------------------- + ArrayPtr getWriteBuffer() override; + void write(const void* buffer, size_t size) override; + +private: + Array vector; + byte* fillPos; + + void grow(size_t minSize); +}; + +// ======================================================================================= +// File descriptor I/O + +class AutoCloseFd { + // A wrapper around a file descriptor which automatically closes the descriptor when destroyed. + // The wrapper supports move construction for transferring ownership of the descriptor. If + // close() returns an error, the destructor throws an exception, UNLESS the destructor is being + // called during unwind from another exception, in which case the close error is ignored. + // + // If your code is not exception-safe, you should not use AutoCloseFd. In this case you will + // have to call close() yourself and handle errors appropriately. + +public: + inline AutoCloseFd(): fd(-1) {} + inline AutoCloseFd(decltype(nullptr)): fd(-1) {} + inline explicit AutoCloseFd(int fd): fd(fd) {} + inline AutoCloseFd(AutoCloseFd&& other) noexcept: fd(other.fd) { other.fd = -1; } + KJ_DISALLOW_COPY(AutoCloseFd); + ~AutoCloseFd() noexcept(false); + + inline AutoCloseFd& operator=(AutoCloseFd&& other) { + AutoCloseFd old(kj::mv(*this)); + fd = other.fd; + other.fd = -1; + return *this; + } + + inline AutoCloseFd& operator=(decltype(nullptr)) { + AutoCloseFd old(kj::mv(*this)); + return *this; + } + + inline operator int() const { return fd; } + inline int get() const { return fd; } + + operator bool() const = delete; + // Deleting this operator prevents accidental use in boolean contexts, which + // the int conversion operator above would otherwise allow. + + inline bool operator==(decltype(nullptr)) { return fd < 0; } + inline bool operator!=(decltype(nullptr)) { return fd >= 0; } + +private: + int fd; + UnwindDetector unwindDetector; +}; + +inline auto KJ_STRINGIFY(const AutoCloseFd& fd) + -> decltype(kj::toCharSequence(implicitCast(fd))) { + return kj::toCharSequence(implicitCast(fd)); +} + +class FdInputStream: public InputStream { + // An InputStream wrapping a file descriptor. + +public: + explicit FdInputStream(int fd): fd(fd) {} + explicit FdInputStream(AutoCloseFd fd): fd(fd), autoclose(mv(fd)) {} + KJ_DISALLOW_COPY(FdInputStream); + ~FdInputStream() noexcept(false); + + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + + inline int getFd() const { return fd; } + +private: + int fd; + AutoCloseFd autoclose; +}; + +class FdOutputStream: public OutputStream { + // An OutputStream wrapping a file descriptor. + +public: + explicit FdOutputStream(int fd): fd(fd) {} + explicit FdOutputStream(AutoCloseFd fd): fd(fd), autoclose(mv(fd)) {} + KJ_DISALLOW_COPY(FdOutputStream); + ~FdOutputStream() noexcept(false); + + void write(const void* buffer, size_t size) override; + void write(ArrayPtr> pieces) override; + + inline int getFd() const { return fd; } + +private: + int fd; + AutoCloseFd autoclose; +}; + +// ======================================================================================= +// Win32 Handle I/O + +#ifdef _WIN32 + +class AutoCloseHandle { + // A wrapper around a Win32 HANDLE which automatically closes the handle when destroyed. + // The wrapper supports move construction for transferring ownership of the handle. If + // CloseHandle() returns an error, the destructor throws an exception, UNLESS the destructor is + // being called during unwind from another exception, in which case the close error is ignored. + // + // If your code is not exception-safe, you should not use AutoCloseHandle. In this case you will + // have to call close() yourself and handle errors appropriately. + +public: + inline AutoCloseHandle(): handle((void*)-1) {} + inline AutoCloseHandle(decltype(nullptr)): handle((void*)-1) {} + inline explicit AutoCloseHandle(void* handle): handle(handle) {} + inline AutoCloseHandle(AutoCloseHandle&& other) noexcept: handle(other.handle) { + other.handle = (void*)-1; + } + KJ_DISALLOW_COPY(AutoCloseHandle); + ~AutoCloseHandle() noexcept(false); + + inline AutoCloseHandle& operator=(AutoCloseHandle&& other) { + AutoCloseHandle old(kj::mv(*this)); + handle = other.handle; + other.handle = (void*)-1; + return *this; + } + + inline AutoCloseHandle& operator=(decltype(nullptr)) { + AutoCloseHandle old(kj::mv(*this)); + return *this; + } + + inline operator void*() const { return handle; } + inline void* get() const { return handle; } + + operator bool() const = delete; + // Deleting this operator prevents accidental use in boolean contexts, which + // the void* conversion operator above would otherwise allow. + + inline bool operator==(decltype(nullptr)) { return handle != (void*)-1; } + inline bool operator!=(decltype(nullptr)) { return handle == (void*)-1; } + +private: + void* handle; // -1 (aka INVALID_HANDLE_VALUE) if not valid. +}; + +class HandleInputStream: public InputStream { + // An InputStream wrapping a Win32 HANDLE. + +public: + explicit HandleInputStream(void* handle): handle(handle) {} + explicit HandleInputStream(AutoCloseHandle handle): handle(handle), autoclose(mv(handle)) {} + KJ_DISALLOW_COPY(HandleInputStream); + ~HandleInputStream() noexcept(false); + + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + +private: + void* handle; + AutoCloseHandle autoclose; +}; + +class HandleOutputStream: public OutputStream { + // An OutputStream wrapping a Win32 HANDLE. + +public: + explicit HandleOutputStream(void* handle): handle(handle) {} + explicit HandleOutputStream(AutoCloseHandle handle): handle(handle), autoclose(mv(handle)) {} + KJ_DISALLOW_COPY(HandleOutputStream); + ~HandleOutputStream() noexcept(false); + + void write(const void* buffer, size_t size) override; + +private: + void* handle; + AutoCloseHandle autoclose; +}; + +#endif // _WIN32 + +} // namespace kj + +#endif // KJ_IO_H_ diff --git a/phonelibs/capnp-cpp/include/kj/main.h b/phonelibs/capnp-cpp/include/kj/main.h new file mode 100644 index 00000000000000..4dcd804fd4d224 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/main.h @@ -0,0 +1,407 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_MAIN_H_ +#define KJ_MAIN_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "array.h" +#include "string.h" +#include "vector.h" +#include "function.h" + +namespace kj { + +class ProcessContext { + // Context for command-line programs. + +public: + virtual StringPtr getProgramName() = 0; + // Get argv[0] as passed to main(). + + KJ_NORETURN(virtual void exit()) = 0; + // Indicates program completion. The program is considered successful unless `error()` was + // called. Typically this exits with _Exit(), meaning that the stack is not unwound, buffers + // are not flushed, etc. -- it is the responsibility of the caller to flush any buffers that + // matter. However, an alternate context implementation e.g. for unit testing purposes could + // choose to throw an exception instead. + // + // At first this approach may sound crazy. Isn't it much better to shut down cleanly? What if + // you lose data? However, it turns out that if you look at each common class of program, _Exit() + // is almost always preferable. Let's break it down: + // + // * Commands: A typical program you might run from the command line is single-threaded and + // exits quickly and deterministically. Commands often use buffered I/O and need to flush + // those buffers before exit. However, most of the work performed by destructors is not + // flushing buffers, but rather freeing up memory, placing objects into freelists, and closing + // file descriptors. All of this is irrelevant if the process is about to exit anyway, and + // for a command that runs quickly, time wasted freeing heap space may make a real difference + // in the overall runtime of a script. Meanwhile, it is usually easy to determine exactly what + // resources need to be flushed before exit, and easy to tell if they are not being flushed + // (because the command fails to produce the expected output). Therefore, it is reasonably + // easy for commands to explicitly ensure all output is flushed before exiting, and it is + // probably a good idea for them to do so anyway, because write failures should be detected + // and handled. For commands, a good strategy is to allocate any objects that require clean + // destruction on the stack, and allow them to go out of scope before the command exits. + // Meanwhile, any resources which do not need to be cleaned up should be allocated as members + // of the command's main class, whose destructor normally will not be called. + // + // * Interactive apps: Programs that interact with the user (whether they be graphical apps + // with windows or console-based apps like emacs) generally exit only when the user asks them + // to. Such applications may store large data structures in memory which need to be synced + // to disk, such as documents or user preferences. However, relying on stack unwind or global + // destructors as the mechanism for ensuring such syncing occurs is probably wrong. First of + // all, it's 2013, and applications ought to be actively syncing changes to non-volatile + // storage the moment those changes are made. Applications can crash at any time and a crash + // should never lose data that is more than half a second old. Meanwhile, if a user actually + // does try to close an application while unsaved changes exist, the application UI should + // prompt the user to decide what to do. Such a UI mechanism is obviously too high level to + // be implemented via destructors, so KJ's use of _Exit() shouldn't make a difference here. + // + // * Servers: A good server is fault-tolerant, prepared for the possibility that at any time + // it could crash, the OS could decide to kill it off, or the machine it is running on could + // just die. So, using _Exit() should be no problem. In fact, servers generally never even + // call exit anyway; they are killed externally. + // + // * Batch jobs: A long-running batch job is something between a command and a server. It + // probably knows exactly what needs to be flushed before exiting, and it probably should be + // fault-tolerant. + // + // Meanwhile, regardless of program type, if you are adhering to KJ style, then the use of + // _Exit() shouldn't be a problem anyway: + // + // * KJ style forbids global mutable state (singletons) in general and global constructors and + // destructors in particular. Therefore, everything that could possibly need cleanup either + // lives on the stack or is transitively owned by something living on the stack. + // + // * Calling exit() simply means "Don't clean up anything older than this stack frame.". If you + // have resources that require cleanup before exit, make sure they are owned by stack frames + // beyond the one that eventually calls exit(). To be as safe as possible, don't place any + // state in your program's main class, and don't call exit() yourself. Then, runMainAndExit() + // will do it, and the only thing on the stack at that time will be your main class, which + // has no state anyway. + // + // TODO(someday): Perhaps we should use the new std::quick_exit(), so that at_quick_exit() is + // available for those who really think they need it. Unfortunately, it is not yet available + // on many platforms. + + virtual void warning(StringPtr message) = 0; + // Print the given message to standard error. A newline is printed after the message if it + // doesn't already have one. + + virtual void error(StringPtr message) = 0; + // Like `warning()`, but also sets a flag indicating that the process has failed, and that when + // it eventually exits it should indicate an error status. + + KJ_NORETURN(virtual void exitError(StringPtr message)) = 0; + // Equivalent to `error(message)` followed by `exit()`. + + KJ_NORETURN(virtual void exitInfo(StringPtr message)) = 0; + // Displays the given non-error message to the user and then calls `exit()`. This is used to + // implement things like --help. + + virtual void increaseLoggingVerbosity() = 0; + // Increase the level of detail produced by the debug logging system. `MainBuilder` invokes + // this if the caller uses the -v flag. + + // TODO(someday): Add interfaces representing standard OS resources like the filesystem, so that + // these things can be mocked out. +}; + +class TopLevelProcessContext final: public ProcessContext { + // A ProcessContext implementation appropriate for use at the actual entry point of a process + // (as opposed to when you are trying to call a program's main function from within some other + // program). This implementation writes errors to stderr, and its `exit()` method actually + // calls the C `quick_exit()` function. + +public: + explicit TopLevelProcessContext(StringPtr programName); + + struct CleanShutdownException { int exitCode; }; + // If the environment variable KJ_CLEAN_SHUTDOWN is set, then exit() will actually throw this + // exception rather than exiting. `kj::runMain()` catches this exception and returns normally. + // This is useful primarily for testing purposes, to assist tools like memory leak checkers that + // are easily confused by quick_exit(). + + StringPtr getProgramName() override; + KJ_NORETURN(void exit() override); + void warning(StringPtr message) override; + void error(StringPtr message) override; + KJ_NORETURN(void exitError(StringPtr message) override); + KJ_NORETURN(void exitInfo(StringPtr message) override); + void increaseLoggingVerbosity() override; + +private: + StringPtr programName; + bool cleanShutdown; + bool hadErrors = false; +}; + +typedef Function params)> MainFunc; + +int runMainAndExit(ProcessContext& context, MainFunc&& func, int argc, char* argv[]); +// Runs the given main function and then exits using the given context. If an exception is thrown, +// this will catch it, report it via the context and exit with an error code. +// +// Normally this function does not return, because returning would probably lead to wasting time +// on cleanup when the process is just going to exit anyway. However, to facilitate memory leak +// checkers and other tools that require a clean shutdown to do their job, if the environment +// variable KJ_CLEAN_SHUTDOWN is set, the function will in fact return an exit code, which should +// then be returned from main(). +// +// Most users will use the KJ_MAIN() macro rather than call this function directly. + +#define KJ_MAIN(MainClass) \ + int main(int argc, char* argv[]) { \ + ::kj::TopLevelProcessContext context(argv[0]); \ + MainClass mainObject(context); \ + return ::kj::runMainAndExit(context, mainObject.getMain(), argc, argv); \ + } +// Convenience macro for declaring a main function based on the given class. The class must have +// a constructor that accepts a ProcessContext& and a method getMain() which returns +// kj::MainFunc (probably building it using a MainBuilder). + +class MainBuilder { + // Builds a main() function with nice argument parsing. As options and arguments are parsed, + // corresponding callbacks are called, so that you never have to write a massive switch() + // statement to interpret arguments. Additionally, this approach encourages you to write + // main classes that have a reasonable API that can be used as an alternative to their + // command-line interface. + // + // All StringPtrs passed to MainBuilder must remain valid until option parsing completes. The + // assumption is that these strings will all be literals, making this an easy requirement. If + // not, consider allocating them in an Arena. + // + // Some flags are automatically recognized by the main functions built by this class: + // --help: Prints help text and exits. The help text is constructed based on the + // information you provide to the builder as you define each flag. + // --verbose: Increase logging verbosity. + // --version: Print version information and exit. + // + // Example usage: + // + // class FooMain { + // public: + // FooMain(kj::ProcessContext& context): context(context) {} + // + // bool setAll() { all = true; return true; } + // // Enable the --all flag. + // + // kj::MainBuilder::Validity setOutput(kj::StringPtr name) { + // // Set the output file. + // + // if (name.endsWith(".foo")) { + // outputFile = name; + // return true; + // } else { + // return "Output file must have extension .foo."; + // } + // } + // + // kj::MainBuilder::Validity processInput(kj::StringPtr name) { + // // Process an input file. + // + // if (!exists(name)) { + // return kj::str(name, ": file not found"); + // } + // // ... process the input file ... + // return true; + // } + // + // kj::MainFunc getMain() { + // return MainBuilder(context, "Foo Builder v1.5", "Reads s and builds a Foo.") + // .addOption({'a', "all"}, KJ_BIND_METHOD(*this, setAll), + // "Frob all the widgets. Otherwise, only some widgets are frobbed.") + // .addOptionWithArg({'o', "output"}, KJ_BIND_METHOD(*this, setOutput), + // "", "Output to . Must be a .foo file.") + // .expectOneOrMoreArgs("", KJ_BIND_METHOD(*this, processInput)) + // .build(); + // } + // + // private: + // bool all = false; + // kj::StringPtr outputFile; + // kj::ProcessContext& context; + // }; + +public: + MainBuilder(ProcessContext& context, StringPtr version, + StringPtr briefDescription, StringPtr extendedDescription = nullptr); + ~MainBuilder() noexcept(false); + + class OptionName { + public: + OptionName() = default; + inline OptionName(char shortName): isLong(false), shortName(shortName) {} + inline OptionName(const char* longName): isLong(true), longName(longName) {} + + private: + bool isLong; + union { + char shortName; + const char* longName; + }; + friend class MainBuilder; + }; + + class Validity { + public: + inline Validity(bool valid) { + if (!valid) errorMessage = heapString("invalid argument"); + } + inline Validity(const char* errorMessage) + : errorMessage(heapString(errorMessage)) {} + inline Validity(String&& errorMessage) + : errorMessage(kj::mv(errorMessage)) {} + + inline const Maybe& getError() const { return errorMessage; } + inline Maybe releaseError() { return kj::mv(errorMessage); } + + private: + Maybe errorMessage; + friend class MainBuilder; + }; + + MainBuilder& addOption(std::initializer_list names, Function callback, + StringPtr helpText); + // Defines a new option (flag). `names` is a list of characters and strings that can be used to + // specify the option on the command line. Single-character names are used with "-" while string + // names are used with "--". `helpText` is a natural-language description of the flag. + // + // `callback` is called when the option is seen. Its return value indicates whether the option + // was accepted. If not, further option processing stops, and error is written, and the process + // exits. + // + // Example: + // + // builder.addOption({'a', "all"}, KJ_BIND_METHOD(*this, showAll), "Show all files."); + // + // This option could be specified in the following ways: + // + // -a + // --all + // + // Note that single-character option names can be combined into a single argument. For example, + // `-abcd` is equivalent to `-a -b -c -d`. + // + // The help text for this option would look like: + // + // -a, --all + // Show all files. + // + // Note that help text is automatically word-wrapped. + + MainBuilder& addOptionWithArg(std::initializer_list names, + Function callback, + StringPtr argumentTitle, StringPtr helpText); + // Like `addOption()`, but adds an option which accepts an argument. `argumentTitle` is used in + // the help text. The argument text is passed to the callback. + // + // Example: + // + // builder.addOptionWithArg({'o', "output"}, KJ_BIND_METHOD(*this, setOutput), + // "", "Output to ."); + // + // This option could be specified with an argument of "foo" in the following ways: + // + // -ofoo + // -o foo + // --output=foo + // --output foo + // + // Note that single-character option names can be combined, but only the last option can have an + // argument, since the characters after the option letter are interpreted as the argument. E.g. + // `-abofoo` would be equivalent to `-a -b -o foo`. + // + // The help text for this option would look like: + // + // -o FILENAME, --output=FILENAME + // Output to FILENAME. + + MainBuilder& addSubCommand(StringPtr name, Function getSubParser, + StringPtr briefHelpText); + // If exactly the given name is seen as an argument, invoke getSubParser() and then pass all + // remaining arguments to the parser it returns. This is useful for implementing commands which + // have lots of sub-commands, like "git" (which has sub-commands "checkout", "branch", "pull", + // etc.). + // + // `getSubParser` is only called if the command is seen. This avoids building main functions + // for commands that aren't used. + // + // `briefHelpText` should be brief enough to show immediately after the command name on a single + // line. It will not be wrapped. Users can use the built-in "help" command to get extended + // help on a particular command. + + MainBuilder& expectArg(StringPtr title, Function callback); + MainBuilder& expectOptionalArg(StringPtr title, Function callback); + MainBuilder& expectZeroOrMoreArgs(StringPtr title, Function callback); + MainBuilder& expectOneOrMoreArgs(StringPtr title, Function callback); + // Set callbacks to handle arguments. `expectArg()` and `expectOptionalArg()` specify positional + // arguments with special handling, while `expect{Zero,One}OrMoreArgs()` specifies a handler for + // an argument list (the handler is called once for each argument in the list). `title` + // specifies how the argument should be represented in the usage text. + // + // All options callbacks are called before argument callbacks, regardless of their ordering on + // the command line. This matches GNU getopt's behavior of permuting non-flag arguments to the + // end of the argument list. Also matching getopt, the special option "--" indicates that the + // rest of the command line is all arguments, not options, even if they start with '-'. + // + // The interpretation of positional arguments is fairly flexible. The non-optional arguments can + // be expected at the beginning, end, or in the middle. If more arguments are specified than + // the number of non-optional args, they are assigned to the optional argument handlers in the + // order of registration. + // + // For example, say you called: + // builder.expectArg("", ...); + // builder.expectOptionalArg("", ...); + // builder.expectArg("", ...); + // builder.expectZeroOrMoreArgs("", ...); + // builder.expectArg("", ...); + // + // This command requires at least three arguments: foo, baz, and corge. If four arguments are + // given, the second is assigned to bar. If five or more arguments are specified, then the + // arguments between the third and last are assigned to qux. Note that it never makes sense + // to call `expect*OrMoreArgs()` more than once since only the first call would ever be used. + // + // In practice, you probably shouldn't create such complicated commands as in the above example. + // But, this flexibility seems necessary to support commands where the first argument is special + // as well as commands (like `cp`) where the last argument is special. + + MainBuilder& callAfterParsing(Function callback); + // Call the given function after all arguments have been parsed. + + MainFunc build(); + // Build the "main" function, which simply parses the arguments. Once this returns, the + // `MainBuilder` is no longer valid. + +private: + struct Impl; + Own impl; + + class MainImpl; +}; + +} // namespace kj + +#endif // KJ_MAIN_H_ diff --git a/phonelibs/capnp-cpp/include/kj/memory.h b/phonelibs/capnp-cpp/include/kj/memory.h new file mode 100644 index 00000000000000..60912b0a344fce --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/memory.h @@ -0,0 +1,406 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_MEMORY_H_ +#define KJ_MEMORY_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" + +namespace kj { + +// ======================================================================================= +// Disposer -- Implementation details. + +class Disposer { + // Abstract interface for a thing that "disposes" of objects, where "disposing" usually means + // calling the destructor followed by freeing the underlying memory. `Own` encapsulates an + // object pointer with corresponding Disposer. + // + // Few developers will ever touch this interface. It is primarily useful for those implementing + // custom memory allocators. + +protected: + // Do not declare a destructor, as doing so will force a global initializer for each HeapDisposer + // instance. Eww! + + virtual void disposeImpl(void* pointer) const = 0; + // Disposes of the object, given a pointer to the beginning of the object. If the object is + // polymorphic, this pointer is determined by dynamic_cast(). For non-polymorphic types, + // Own does not allow any casting, so the pointer exactly matches the original one given to + // Own. + +public: + + template + void dispose(T* object) const; + // Helper wrapper around disposeImpl(). + // + // If T is polymorphic, calls `disposeImpl(dynamic_cast(object))`, otherwise calls + // `disposeImpl(implicitCast(object))`. + // + // Callers must not call dispose() on the same pointer twice, even if the first call throws + // an exception. + +private: + template + struct Dispose_; +}; + +template +class DestructorOnlyDisposer: public Disposer { + // A disposer that merely calls the type's destructor and nothing else. + +public: + static const DestructorOnlyDisposer instance; + + void disposeImpl(void* pointer) const override { + reinterpret_cast(pointer)->~T(); + } +}; + +template +const DestructorOnlyDisposer DestructorOnlyDisposer::instance = DestructorOnlyDisposer(); + +class NullDisposer: public Disposer { + // A disposer that does nothing. + +public: + static const NullDisposer instance; + + void disposeImpl(void* pointer) const override {} +}; + +// ======================================================================================= +// Own -- An owned pointer. + +template +class Own { + // A transferrable title to a T. When an Own goes out of scope, the object's Disposer is + // called to dispose of it. An Own can be efficiently passed by move, without relocating the + // underlying object; this transfers ownership. + // + // This is much like std::unique_ptr, except: + // - You cannot release(). An owned object is not necessarily allocated with new (see next + // point), so it would be hard to use release() correctly. + // - The deleter is made polymorphic by virtual call rather than by template. This is much + // more powerful -- it allows the use of custom allocators, freelists, etc. This could + // _almost_ be accomplished with unique_ptr by forcing everyone to use something like + // std::unique_ptr, except that things get hairy in the presence of multiple + // inheritance and upcasting, and anyway if you force everyone to use a custom deleter + // then you've lost any benefit to interoperating with the "standard" unique_ptr. + +public: + KJ_DISALLOW_COPY(Own); + inline Own(): disposer(nullptr), ptr(nullptr) {} + inline Own(Own&& other) noexcept + : disposer(other.disposer), ptr(other.ptr) { other.ptr = nullptr; } + inline Own(Own>&& other) noexcept + : disposer(other.disposer), ptr(other.ptr) { other.ptr = nullptr; } + template ()>> + inline Own(Own&& other) noexcept + : disposer(other.disposer), ptr(other.ptr) { + static_assert(__is_polymorphic(T), + "Casting owned pointers requires that the target type is polymorphic."); + other.ptr = nullptr; + } + inline Own(T* ptr, const Disposer& disposer) noexcept: disposer(&disposer), ptr(ptr) {} + + ~Own() noexcept(false) { dispose(); } + + inline Own& operator=(Own&& other) { + // Move-assingnment operator. + + // Careful, this might own `other`. Therefore we have to transfer the pointers first, then + // dispose. + const Disposer* disposerCopy = disposer; + T* ptrCopy = ptr; + disposer = other.disposer; + ptr = other.ptr; + other.ptr = nullptr; + if (ptrCopy != nullptr) { + disposerCopy->dispose(const_cast*>(ptrCopy)); + } + return *this; + } + + inline Own& operator=(decltype(nullptr)) { + dispose(); + return *this; + } + + template + Own downcast() { + // Downcast the pointer to Own, destroying the original pointer. If this pointer does not + // actually point at an instance of U, the results are undefined (throws an exception in debug + // mode if RTTI is enabled, otherwise you're on your own). + + Own result; + if (ptr != nullptr) { + result.ptr = &kj::downcast(*ptr); + result.disposer = disposer; + ptr = nullptr; + } + return result; + } + +#define NULLCHECK KJ_IREQUIRE(ptr != nullptr, "null Own<> dereference") + inline T* operator->() { NULLCHECK; return ptr; } + inline const T* operator->() const { NULLCHECK; return ptr; } + inline T& operator*() { NULLCHECK; return *ptr; } + inline const T& operator*() const { NULLCHECK; return *ptr; } +#undef NULLCHECK + inline T* get() { return ptr; } + inline const T* get() const { return ptr; } + inline operator T*() { return ptr; } + inline operator const T*() const { return ptr; } + +private: + const Disposer* disposer; // Only valid if ptr != nullptr. + T* ptr; + + inline explicit Own(decltype(nullptr)): disposer(nullptr), ptr(nullptr) {} + + inline bool operator==(decltype(nullptr)) { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) { return ptr != nullptr; } + // Only called by Maybe>. + + inline void dispose() { + // Make sure that if an exception is thrown, we are left with a null ptr, so we won't possibly + // dispose again. + T* ptrCopy = ptr; + if (ptrCopy != nullptr) { + ptr = nullptr; + disposer->dispose(const_cast*>(ptrCopy)); + } + } + + template + friend class Own; + friend class Maybe>; +}; + +namespace _ { // private + +template +class OwnOwn { +public: + inline OwnOwn(Own&& value) noexcept: value(kj::mv(value)) {} + + inline Own& operator*() & { return value; } + inline const Own& operator*() const & { return value; } + inline Own&& operator*() && { return kj::mv(value); } + inline const Own&& operator*() const && { return kj::mv(value); } + inline Own* operator->() { return &value; } + inline const Own* operator->() const { return &value; } + inline operator Own*() { return value ? &value : nullptr; } + inline operator const Own*() const { return value ? &value : nullptr; } + +private: + Own value; +}; + +template +OwnOwn readMaybe(Maybe>&& maybe) { return OwnOwn(kj::mv(maybe.ptr)); } +template +Own* readMaybe(Maybe>& maybe) { return maybe.ptr ? &maybe.ptr : nullptr; } +template +const Own* readMaybe(const Maybe>& maybe) { return maybe.ptr ? &maybe.ptr : nullptr; } + +} // namespace _ (private) + +template +class Maybe> { +public: + inline Maybe(): ptr(nullptr) {} + inline Maybe(Own&& t) noexcept: ptr(kj::mv(t)) {} + inline Maybe(Maybe&& other) noexcept: ptr(kj::mv(other.ptr)) {} + + template + inline Maybe(Maybe>&& other): ptr(mv(other.ptr)) {} + template + inline Maybe(Own&& other): ptr(mv(other)) {} + + inline Maybe(decltype(nullptr)) noexcept: ptr(nullptr) {} + + inline operator Maybe() { return ptr.get(); } + inline operator Maybe() const { return ptr.get(); } + + inline Maybe& operator=(Maybe&& other) { ptr = kj::mv(other.ptr); return *this; } + + inline bool operator==(decltype(nullptr)) const { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return ptr != nullptr; } + + Own& orDefault(Own& defaultValue) { + if (ptr == nullptr) { + return defaultValue; + } else { + return ptr; + } + } + const Own& orDefault(const Own& defaultValue) const { + if (ptr == nullptr) { + return defaultValue; + } else { + return ptr; + } + } + + template + auto map(Func&& f) & -> Maybe&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(ptr); + } + } + + template + auto map(Func&& f) const & -> Maybe&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(ptr); + } + } + + template + auto map(Func&& f) && -> Maybe&&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(ptr)); + } + } + + template + auto map(Func&& f) const && -> Maybe&&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(ptr)); + } + } + +private: + Own ptr; + + template + friend class Maybe; + template + friend _::OwnOwn _::readMaybe(Maybe>&& maybe); + template + friend Own* _::readMaybe(Maybe>& maybe); + template + friend const Own* _::readMaybe(const Maybe>& maybe); +}; + +namespace _ { // private + +template +class HeapDisposer final: public Disposer { +public: + virtual void disposeImpl(void* pointer) const override { delete reinterpret_cast(pointer); } + + static const HeapDisposer instance; +}; + +template +const HeapDisposer HeapDisposer::instance = HeapDisposer(); + +} // namespace _ (private) + +template +Own heap(Params&&... params) { + // heap(...) allocates a T on the heap, forwarding the parameters to its constructor. The + // exact heap implementation is unspecified -- for now it is operator new, but you should not + // assume this. (Since we know the object size at delete time, we could actually implement an + // allocator that is more efficient than operator new.) + + return Own(new T(kj::fwd(params)...), _::HeapDisposer::instance); +} + +template +Own> heap(T&& orig) { + // Allocate a copy (or move) of the argument on the heap. + // + // The purpose of this overload is to allow you to omit the template parameter as there is only + // one argument and the purpose is to copy it. + + typedef Decay T2; + return Own(new T2(kj::fwd(orig)), _::HeapDisposer::instance); +} + +// ======================================================================================= +// SpaceFor -- assists in manual allocation + +template +class SpaceFor { + // A class which has the same size and alignment as T but does not call its constructor or + // destructor automatically. Instead, call construct() to construct a T in the space, which + // returns an Own which will take care of calling T's destructor later. + +public: + inline SpaceFor() {} + inline ~SpaceFor() {} + + template + Own construct(Params&&... params) { + ctor(value, kj::fwd(params)...); + return Own(&value, DestructorOnlyDisposer::instance); + } + +private: + union { + T value; + }; +}; + +// ======================================================================================= +// Inline implementation details + +template +struct Disposer::Dispose_ { + static void dispose(T* object, const Disposer& disposer) { + // Note that dynamic_cast does not require RTTI to be enabled, because the offset to + // the top of the object is in the vtable -- as it obviously needs to be to correctly implement + // operator delete. + disposer.disposeImpl(dynamic_cast(object)); + } +}; +template +struct Disposer::Dispose_ { + static void dispose(T* object, const Disposer& disposer) { + disposer.disposeImpl(static_cast(object)); + } +}; + +template +void Disposer::dispose(T* object) const { + Dispose_::dispose(object, *this); +} + +} // namespace kj + +#endif // KJ_MEMORY_H_ diff --git a/phonelibs/capnp-cpp/include/kj/mutex.h b/phonelibs/capnp-cpp/include/kj/mutex.h new file mode 100644 index 00000000000000..d211ebfeb1c603 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/mutex.h @@ -0,0 +1,369 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_MUTEX_H_ +#define KJ_MUTEX_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" +#include + +#if __linux__ && !defined(KJ_USE_FUTEX) +#define KJ_USE_FUTEX 1 +#endif + +#if !KJ_USE_FUTEX && !_WIN32 +// On Linux we use futex. On other platforms we wrap pthreads. +// TODO(someday): Write efficient low-level locking primitives for other platforms. +#include +#endif + +namespace kj { + +// ======================================================================================= +// Private details -- public interfaces follow below. + +namespace _ { // private + +class Mutex { + // Internal implementation details. See `MutexGuarded`. + +public: + Mutex(); + ~Mutex(); + KJ_DISALLOW_COPY(Mutex); + + enum Exclusivity { + EXCLUSIVE, + SHARED + }; + + void lock(Exclusivity exclusivity); + void unlock(Exclusivity exclusivity); + + void assertLockedByCaller(Exclusivity exclusivity); + // In debug mode, assert that the mutex is locked by the calling thread, or if that is + // non-trivial, assert that the mutex is locked (which should be good enough to catch problems + // in unit tests). In non-debug builds, do nothing. + +private: +#if KJ_USE_FUTEX + uint futex; + // bit 31 (msb) = set if exclusive lock held + // bit 30 (msb) = set if threads are waiting for exclusive lock + // bits 0-29 = count of readers; If an exclusive lock is held, this is the count of threads + // waiting for a read lock, otherwise it is the count of threads that currently hold a read + // lock. + + static constexpr uint EXCLUSIVE_HELD = 1u << 31; + static constexpr uint EXCLUSIVE_REQUESTED = 1u << 30; + static constexpr uint SHARED_COUNT_MASK = EXCLUSIVE_REQUESTED - 1; + +#elif _WIN32 + uintptr_t srwLock; // Actually an SRWLOCK, but don't want to #include in header. + +#else + mutable pthread_rwlock_t mutex; +#endif +}; + +class Once { + // Internal implementation details. See `Lazy`. + +public: +#if KJ_USE_FUTEX + inline Once(bool startInitialized = false) + : futex(startInitialized ? INITIALIZED : UNINITIALIZED) {} +#else + Once(bool startInitialized = false); + ~Once(); +#endif + KJ_DISALLOW_COPY(Once); + + class Initializer { + public: + virtual void run() = 0; + }; + + void runOnce(Initializer& init); + +#if _WIN32 // TODO(perf): Can we make this inline on win32 somehow? + bool isInitialized() noexcept; + +#else + inline bool isInitialized() noexcept { + // Fast path check to see if runOnce() would simply return immediately. +#if KJ_USE_FUTEX + return __atomic_load_n(&futex, __ATOMIC_ACQUIRE) == INITIALIZED; +#else + return __atomic_load_n(&state, __ATOMIC_ACQUIRE) == INITIALIZED; +#endif + } +#endif + + void reset(); + // Returns the state from initialized to uninitialized. It is an error to call this when + // not already initialized, or when runOnce() or isInitialized() might be called concurrently in + // another thread. + +private: +#if KJ_USE_FUTEX + uint futex; + + enum State { + UNINITIALIZED, + INITIALIZING, + INITIALIZING_WITH_WAITERS, + INITIALIZED + }; + +#elif _WIN32 + uintptr_t initOnce; // Actually an INIT_ONCE, but don't want to #include in header. + +#else + enum State { + UNINITIALIZED, + INITIALIZED + }; + State state; + pthread_mutex_t mutex; +#endif +}; + +} // namespace _ (private) + +// ======================================================================================= +// Public interface + +template +class Locked { + // Return type for `MutexGuarded::lock()`. `Locked` provides access to the bounded object + // and unlocks the mutex when it goes out of scope. + +public: + KJ_DISALLOW_COPY(Locked); + inline Locked(): mutex(nullptr), ptr(nullptr) {} + inline Locked(Locked&& other): mutex(other.mutex), ptr(other.ptr) { + other.mutex = nullptr; + other.ptr = nullptr; + } + inline ~Locked() { + if (mutex != nullptr) mutex->unlock(isConst() ? _::Mutex::SHARED : _::Mutex::EXCLUSIVE); + } + + inline Locked& operator=(Locked&& other) { + if (mutex != nullptr) mutex->unlock(isConst() ? _::Mutex::SHARED : _::Mutex::EXCLUSIVE); + mutex = other.mutex; + ptr = other.ptr; + other.mutex = nullptr; + other.ptr = nullptr; + return *this; + } + + inline void release() { + if (mutex != nullptr) mutex->unlock(isConst() ? _::Mutex::SHARED : _::Mutex::EXCLUSIVE); + mutex = nullptr; + ptr = nullptr; + } + + inline T* operator->() { return ptr; } + inline const T* operator->() const { return ptr; } + inline T& operator*() { return *ptr; } + inline const T& operator*() const { return *ptr; } + inline T* get() { return ptr; } + inline const T* get() const { return ptr; } + inline operator T*() { return ptr; } + inline operator const T*() const { return ptr; } + +private: + _::Mutex* mutex; + T* ptr; + + inline Locked(_::Mutex& mutex, T& value): mutex(&mutex), ptr(&value) {} + + template + friend class MutexGuarded; +}; + +template +class MutexGuarded { + // An object of type T, bounded by a mutex. In order to access the object, you must lock it. + // + // Write locks are not "recursive" -- trying to lock again in a thread that already holds a lock + // will deadlock. Recursive write locks are usually a sign of bad design. + // + // Unfortunately, **READ LOCKS ARE NOT RECURSIVE** either. Common sense says they should be. + // But on many operating systems (BSD, OSX), recursively read-locking a pthread_rwlock is + // actually unsafe. The problem is that writers are "prioritized" over readers, so a read lock + // request will block if any write lock requests are outstanding. So, if thread A takes a read + // lock, thread B requests a write lock (and starts waiting), and then thread A tries to take + // another read lock recursively, the result is deadlock. + +public: + template + explicit MutexGuarded(Params&&... params); + // Initialize the mutex-bounded object by passing the given parameters to its constructor. + + Locked lockExclusive() const; + // Exclusively locks the object and returns it. The returned `Locked` can be passed by + // move, similar to `Own`. + // + // This method is declared `const` in accordance with KJ style rules which say that constness + // should be used to indicate thread-safety. It is safe to share a const pointer between threads, + // but it is not safe to share a mutable pointer. Since the whole point of MutexGuarded is to + // be shared between threads, its methods should be const, even though locking it produces a + // non-const pointer to the contained object. + + Locked lockShared() const; + // Lock the value for shared access. Multiple shared locks can be taken concurrently, but cannot + // be held at the same time as a non-shared lock. + + inline const T& getWithoutLock() const { return value; } + inline T& getWithoutLock() { return value; } + // Escape hatch for cases where some external factor guarantees that it's safe to get the + // value. You should treat these like const_cast -- be highly suspicious of any use. + + inline const T& getAlreadyLockedShared() const; + inline T& getAlreadyLockedShared(); + inline T& getAlreadyLockedExclusive() const; + // Like `getWithoutLock()`, but asserts that the lock is already held by the calling thread. + +private: + mutable _::Mutex mutex; + mutable T value; +}; + +template +class MutexGuarded { + // MutexGuarded cannot guard a const type. This would be pointless anyway, and would complicate + // the implementation of Locked, which uses constness to decide what kind of lock it holds. + static_assert(sizeof(T) < 0, "MutexGuarded's type cannot be const."); +}; + +template +class Lazy { + // A lazily-initialized value. + +public: + template + T& get(Func&& init); + template + const T& get(Func&& init) const; + // The first thread to call get() will invoke the given init function to construct the value. + // Other threads will block until construction completes, then return the same value. + // + // `init` is a functor(typically a lambda) which takes `SpaceFor&` as its parameter and returns + // `Own`. If `init` throws an exception, the exception is propagated out of that thread's + // call to `get()`, and subsequent calls behave as if `get()` hadn't been called at all yet -- + // in other words, subsequent calls retry initialization until it succeeds. + +private: + mutable _::Once once; + mutable SpaceFor space; + mutable Own value; + + template + class InitImpl; +}; + +// ======================================================================================= +// Inline implementation details + +template +template +inline MutexGuarded::MutexGuarded(Params&&... params) + : value(kj::fwd(params)...) {} + +template +inline Locked MutexGuarded::lockExclusive() const { + mutex.lock(_::Mutex::EXCLUSIVE); + return Locked(mutex, value); +} + +template +inline Locked MutexGuarded::lockShared() const { + mutex.lock(_::Mutex::SHARED); + return Locked(mutex, value); +} + +template +inline const T& MutexGuarded::getAlreadyLockedShared() const { +#ifdef KJ_DEBUG + mutex.assertLockedByCaller(_::Mutex::SHARED); +#endif + return value; +} +template +inline T& MutexGuarded::getAlreadyLockedShared() { +#ifdef KJ_DEBUG + mutex.assertLockedByCaller(_::Mutex::SHARED); +#endif + return value; +} +template +inline T& MutexGuarded::getAlreadyLockedExclusive() const { +#ifdef KJ_DEBUG + mutex.assertLockedByCaller(_::Mutex::EXCLUSIVE); +#endif + return const_cast(value); +} + +template +template +class Lazy::InitImpl: public _::Once::Initializer { +public: + inline InitImpl(const Lazy& lazy, Func&& func): lazy(lazy), func(kj::fwd(func)) {} + + void run() override { + lazy.value = func(lazy.space); + } + +private: + const Lazy& lazy; + Func func; +}; + +template +template +inline T& Lazy::get(Func&& init) { + if (!once.isInitialized()) { + InitImpl initImpl(*this, kj::fwd(init)); + once.runOnce(initImpl); + } + return *value; +} + +template +template +inline const T& Lazy::get(Func&& init) const { + if (!once.isInitialized()) { + InitImpl initImpl(*this, kj::fwd(init)); + once.runOnce(initImpl); + } + return *value; +} + +} // namespace kj + +#endif // KJ_MUTEX_H_ diff --git a/phonelibs/capnp-cpp/include/kj/one-of.h b/phonelibs/capnp-cpp/include/kj/one-of.h new file mode 100644 index 00000000000000..6e143c44cf26dd --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/one-of.h @@ -0,0 +1,155 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ONE_OF_H_ +#define KJ_ONE_OF_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" + +namespace kj { + +namespace _ { // private + +template +struct TypeIndex_ { static constexpr uint value = TypeIndex_::value; }; +template +struct TypeIndex_ { static constexpr uint value = i; }; + +} // namespace _ (private) + +template +class OneOf { + template + static inline constexpr uint typeIndex() { return _::TypeIndex_<1, Key, Variants...>::value; } + // Get the 1-based index of Key within the type list Types. + +public: + inline OneOf(): tag(0) {} + OneOf(const OneOf& other) { copyFrom(other); } + OneOf(OneOf&& other) { moveFrom(other); } + ~OneOf() { destroy(); } + + OneOf& operator=(const OneOf& other) { if (tag != 0) destroy(); copyFrom(other); return *this; } + OneOf& operator=(OneOf&& other) { if (tag != 0) destroy(); moveFrom(other); return *this; } + + inline bool operator==(decltype(nullptr)) const { return tag == 0; } + inline bool operator!=(decltype(nullptr)) const { return tag != 0; } + + template + bool is() const { + return tag == typeIndex(); + } + + template + T& get() { + KJ_IREQUIRE(is(), "Must check OneOf::is() before calling get()."); + return *reinterpret_cast(space); + } + template + const T& get() const { + KJ_IREQUIRE(is(), "Must check OneOf::is() before calling get()."); + return *reinterpret_cast(space); + } + + template + T& init(Params&&... params) { + if (tag != 0) destroy(); + ctor(*reinterpret_cast(space), kj::fwd(params)...); + tag = typeIndex(); + return *reinterpret_cast(space); + } + +private: + uint tag; + + static inline constexpr size_t maxSize(size_t a) { + return a; + } + template + static inline constexpr size_t maxSize(size_t a, size_t b, Rest... rest) { + return maxSize(kj::max(a, b), rest...); + } + // Returns the maximum of all the parameters. + // TODO(someday): Generalize the above template and make it common. I tried, but C++ decided to + // be difficult so I cut my losses. + + static constexpr auto spaceSize = maxSize(sizeof(Variants)...); + // TODO(msvc): This constant could just as well go directly inside space's bracket's, where it's + // used, but MSVC suffers a parse error on `...`. + + union { + byte space[spaceSize]; + + void* forceAligned; + // TODO(someday): Use C++11 alignas() once we require GCC 4.8 / Clang 3.3. + }; + + template + inline void doAll(T... t) {} + + template + inline bool destroyVariant() { + if (tag == typeIndex()) { + tag = 0; + dtor(*reinterpret_cast(space)); + } + return false; + } + void destroy() { + doAll(destroyVariant()...); + } + + template + inline bool copyVariantFrom(const OneOf& other) { + if (other.is()) { + ctor(*reinterpret_cast(space), other.get()); + } + return false; + } + void copyFrom(const OneOf& other) { + // Initialize as a copy of `other`. Expects that `this` starts out uninitialized, so the tag + // is invalid. + tag = other.tag; + doAll(copyVariantFrom(other)...); + } + + template + inline bool moveVariantFrom(OneOf& other) { + if (other.is()) { + ctor(*reinterpret_cast(space), kj::mv(other.get())); + } + return false; + } + void moveFrom(OneOf& other) { + // Initialize as a copy of `other`. Expects that `this` starts out uninitialized, so the tag + // is invalid. + tag = other.tag; + doAll(moveVariantFrom(other)...); + } +}; + +} // namespace kj + +#endif // KJ_ONE_OF_H_ diff --git a/phonelibs/capnp-cpp/include/kj/parse/char.h b/phonelibs/capnp-cpp/include/kj/parse/char.h new file mode 100644 index 00000000000000..2e6d51921d86ce --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/parse/char.h @@ -0,0 +1,361 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains parsers useful for character stream inputs, including parsers to parse +// common kinds of tokens like identifiers, numbers, and quoted strings. + +#ifndef KJ_PARSE_CHAR_H_ +#define KJ_PARSE_CHAR_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include "../string.h" +#include + +namespace kj { +namespace parse { + +// ======================================================================================= +// Exact char/string. + +class ExactString_ { +public: + constexpr inline ExactString_(const char* str): str(str) {} + + template + Maybe> operator()(Input& input) const { + const char* ptr = str; + + while (*ptr != '\0') { + if (input.atEnd() || input.current() != *ptr) return nullptr; + input.next(); + ++ptr; + } + + return Tuple<>(); + } + +private: + const char* str; +}; + +constexpr inline ExactString_ exactString(const char* str) { + return ExactString_(str); +} + +template +constexpr ExactlyConst_ exactChar() { + // Returns a parser that matches exactly the character given by the template argument (returning + // no result). + return ExactlyConst_(); +} + +// ======================================================================================= +// Char ranges / sets + +class CharGroup_ { +public: + constexpr inline CharGroup_(): bits{0, 0, 0, 0} {} + + constexpr inline CharGroup_ orRange(unsigned char first, unsigned char last) const { + return CharGroup_(bits[0] | (oneBits(last + 1) & ~oneBits(first )), + bits[1] | (oneBits(last - 63) & ~oneBits(first - 64)), + bits[2] | (oneBits(last - 127) & ~oneBits(first - 128)), + bits[3] | (oneBits(last - 191) & ~oneBits(first - 192))); + } + + constexpr inline CharGroup_ orAny(const char* chars) const { + return *chars == 0 ? *this : orChar(*chars).orAny(chars + 1); + } + + constexpr inline CharGroup_ orChar(unsigned char c) const { + return CharGroup_(bits[0] | bit(c), + bits[1] | bit(c - 64), + bits[2] | bit(c - 128), + bits[3] | bit(c - 256)); + } + + constexpr inline CharGroup_ orGroup(CharGroup_ other) const { + return CharGroup_(bits[0] | other.bits[0], + bits[1] | other.bits[1], + bits[2] | other.bits[2], + bits[3] | other.bits[3]); + } + + constexpr inline CharGroup_ invert() const { + return CharGroup_(~bits[0], ~bits[1], ~bits[2], ~bits[3]); + } + + constexpr inline bool contains(unsigned char c) const { + return (bits[c / 64] & (1ll << (c % 64))) != 0; + } + + template + Maybe operator()(Input& input) const { + if (input.atEnd()) return nullptr; + unsigned char c = input.current(); + if (contains(c)) { + input.next(); + return c; + } else { + return nullptr; + } + } + +private: + typedef unsigned long long Bits64; + + constexpr inline CharGroup_(Bits64 a, Bits64 b, Bits64 c, Bits64 d): bits{a, b, c, d} {} + Bits64 bits[4]; + + static constexpr inline Bits64 oneBits(int count) { + return count <= 0 ? 0ll : count >= 64 ? -1ll : ((1ll << count) - 1); + } + static constexpr inline Bits64 bit(int index) { + return index < 0 ? 0 : index >= 64 ? 0 : (1ll << index); + } +}; + +constexpr inline CharGroup_ charRange(char first, char last) { + // Create a parser which accepts any character in the range from `first` to `last`, inclusive. + // For example: `charRange('a', 'z')` matches all lower-case letters. The parser's result is the + // character matched. + // + // The returned object has methods which can be used to match more characters. The following + // produces a parser which accepts any letter as well as '_', '+', '-', and '.'. + // + // charRange('a', 'z').orRange('A', 'Z').orChar('_').orAny("+-.") + // + // You can also use `.invert()` to match the opposite set of characters. + + return CharGroup_().orRange(first, last); +} + +#if _MSC_VER +#define anyOfChars(chars) CharGroup_().orAny(chars) +// TODO(msvc): MSVC ICEs on the proper definition of `anyOfChars()`, which in turn prevents us from +// building the compiler or schema parser. We don't know why this happens, but Harris found that +// this horrible, horrible hack makes things work. This is awful, but it's better than nothing. +// Hopefully, MSVC will get fixed soon and we'll be able to remove this. +#else +constexpr inline CharGroup_ anyOfChars(const char* chars) { + // Returns a parser that accepts any of the characters in the given string (which should usually + // be a literal). The returned parser is of the same type as returned by `charRange()` -- see + // that function for more info. + + return CharGroup_().orAny(chars); +} +#endif + +// ======================================================================================= + +namespace _ { // private + +struct ArrayToString { + inline String operator()(const Array& arr) const { + return heapString(arr); + } +}; + +} // namespace _ (private) + +template +constexpr inline auto charsToString(SubParser&& subParser) + -> decltype(transform(kj::fwd(subParser), _::ArrayToString())) { + // Wraps a parser that returns Array such that it returns String instead. + return parse::transform(kj::fwd(subParser), _::ArrayToString()); +} + +// ======================================================================================= +// Basic character classes. + +constexpr auto alpha = charRange('a', 'z').orRange('A', 'Z'); +constexpr auto digit = charRange('0', '9'); +constexpr auto alphaNumeric = alpha.orGroup(digit); +constexpr auto nameStart = alpha.orChar('_'); +constexpr auto nameChar = alphaNumeric.orChar('_'); +constexpr auto hexDigit = charRange('0', '9').orRange('a', 'f').orRange('A', 'F'); +constexpr auto octDigit = charRange('0', '7'); +constexpr auto whitespaceChar = anyOfChars(" \f\n\r\t\v"); +constexpr auto controlChar = charRange(0, 0x1f).invert().orGroup(whitespaceChar).invert(); + +constexpr auto whitespace = many(anyOfChars(" \f\n\r\t\v")); + +constexpr auto discardWhitespace = discard(many(discard(anyOfChars(" \f\n\r\t\v")))); +// Like discard(whitespace) but avoids some memory allocation. + +// ======================================================================================= +// Identifiers + +namespace _ { // private + +struct IdentifierToString { + inline String operator()(char first, const Array& rest) const { + String result = heapString(rest.size() + 1); + result[0] = first; + memcpy(result.begin() + 1, rest.begin(), rest.size()); + return result; + } +}; + +} // namespace _ (private) + +constexpr auto identifier = transform(sequence(nameStart, many(nameChar)), _::IdentifierToString()); +// Parses an identifier (e.g. a C variable name). + +// ======================================================================================= +// Integers + +namespace _ { // private + +inline char parseDigit(char c) { + if (c < 'A') return c - '0'; + if (c < 'a') return c - 'A' + 10; + return c - 'a' + 10; +} + +template +struct ParseInteger { + inline uint64_t operator()(const Array& digits) const { + return operator()('0', digits); + } + uint64_t operator()(char first, const Array& digits) const { + uint64_t result = parseDigit(first); + for (char digit: digits) { + result = result * base + parseDigit(digit); + } + return result; + } +}; + + +} // namespace _ (private) + +constexpr auto integer = sequence( + oneOf( + transform(sequence(exactChar<'0'>(), exactChar<'x'>(), oneOrMore(hexDigit)), _::ParseInteger<16>()), + transform(sequence(exactChar<'0'>(), many(octDigit)), _::ParseInteger<8>()), + transform(sequence(charRange('1', '9'), many(digit)), _::ParseInteger<10>())), + notLookingAt(alpha.orAny("_."))); + +// ======================================================================================= +// Numbers (i.e. floats) + +namespace _ { // private + +struct ParseFloat { + double operator()(const Array& digits, + const Maybe>& fraction, + const Maybe, Array>>& exponent) const; +}; + +} // namespace _ (private) + +constexpr auto number = transform( + sequence( + oneOrMore(digit), + optional(sequence(exactChar<'.'>(), many(digit))), + optional(sequence(discard(anyOfChars("eE")), optional(anyOfChars("+-")), many(digit))), + notLookingAt(alpha.orAny("_."))), + _::ParseFloat()); + +// ======================================================================================= +// Quoted strings + +namespace _ { // private + +struct InterpretEscape { + char operator()(char c) const { + switch (c) { + case 'a': return '\a'; + case 'b': return '\b'; + case 'f': return '\f'; + case 'n': return '\n'; + case 'r': return '\r'; + case 't': return '\t'; + case 'v': return '\v'; + default: return c; + } + } +}; + +struct ParseHexEscape { + inline char operator()(char first, char second) const { + return (parseDigit(first) << 4) | parseDigit(second); + } +}; + +struct ParseHexByte { + inline byte operator()(char first, char second) const { + return (parseDigit(first) << 4) | parseDigit(second); + } +}; + +struct ParseOctEscape { + inline char operator()(char first, Maybe second, Maybe third) const { + char result = first - '0'; + KJ_IF_MAYBE(digit1, second) { + result = (result << 3) | (*digit1 - '0'); + KJ_IF_MAYBE(digit2, third) { + result = (result << 3) | (*digit2 - '0'); + } + } + return result; + } +}; + +} // namespace _ (private) + +constexpr auto escapeSequence = + sequence(exactChar<'\\'>(), oneOf( + transform(anyOfChars("abfnrtv'\"\\\?"), _::InterpretEscape()), + transform(sequence(exactChar<'x'>(), hexDigit, hexDigit), _::ParseHexEscape()), + transform(sequence(octDigit, optional(octDigit), optional(octDigit)), + _::ParseOctEscape()))); +// A parser that parses a C-string-style escape sequence (starting with a backslash). Returns +// a char. + +constexpr auto doubleQuotedString = charsToString(sequence( + exactChar<'\"'>(), + many(oneOf(anyOfChars("\\\n\"").invert(), escapeSequence)), + exactChar<'\"'>())); +// Parses a C-style double-quoted string. + +constexpr auto singleQuotedString = charsToString(sequence( + exactChar<'\''>(), + many(oneOf(anyOfChars("\\\n\'").invert(), escapeSequence)), + exactChar<'\''>())); +// Parses a C-style single-quoted string. + +constexpr auto doubleQuotedHexBinary = sequence( + exactChar<'0'>(), exactChar<'x'>(), exactChar<'\"'>(), + oneOrMore(transform(sequence(discardWhitespace, hexDigit, hexDigit), _::ParseHexByte())), + discardWhitespace, + exactChar<'\"'>()); +// Parses a double-quoted hex binary literal. Returns Array. + +} // namespace parse +} // namespace kj + +#endif // KJ_PARSE_CHAR_H_ diff --git a/phonelibs/capnp-cpp/include/kj/parse/common.h b/phonelibs/capnp-cpp/include/kj/parse/common.h new file mode 100644 index 00000000000000..3af3a8760d5e7e --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/parse/common.h @@ -0,0 +1,824 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// Parser combinator framework! +// +// This file declares several functions which construct parsers, usually taking other parsers as +// input, thus making them parser combinators. +// +// A valid parser is any functor which takes a reference to an input cursor (defined below) as its +// input and returns a Maybe. The parser returns null on parse failure, or returns the parsed +// result on success. +// +// An "input cursor" is any type which implements the same interface as IteratorInput, below. Such +// a type acts as a pointer to the current input location. When a parser returns successfully, it +// will have updated the input cursor to point to the position just past the end of what was parsed. +// On failure, the cursor position is unspecified. + +#ifndef KJ_PARSE_COMMON_H_ +#define KJ_PARSE_COMMON_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "../common.h" +#include "../memory.h" +#include "../array.h" +#include "../tuple.h" +#include "../vector.h" +#if _MSC_VER +#include // result_of_t +#endif + +namespace kj { +namespace parse { + +template +class IteratorInput { + // A parser input implementation based on an iterator range. + +public: + IteratorInput(Iterator begin, Iterator end) + : parent(nullptr), pos(begin), end(end), best(begin) {} + explicit IteratorInput(IteratorInput& parent) + : parent(&parent), pos(parent.pos), end(parent.end), best(parent.pos) {} + ~IteratorInput() { + if (parent != nullptr) { + parent->best = kj::max(kj::max(pos, best), parent->best); + } + } + KJ_DISALLOW_COPY(IteratorInput); + + void advanceParent() { + parent->pos = pos; + } + void forgetParent() { + parent = nullptr; + } + + bool atEnd() { return pos == end; } + auto current() -> decltype(*instance()) { + KJ_IREQUIRE(!atEnd()); + return *pos; + } + auto consume() -> decltype(*instance()) { + KJ_IREQUIRE(!atEnd()); + return *pos++; + } + void next() { + KJ_IREQUIRE(!atEnd()); + ++pos; + } + + Iterator getBest() { return kj::max(pos, best); } + + Iterator getPosition() { return pos; } + +private: + IteratorInput* parent; + Iterator pos; + Iterator end; + Iterator best; // furthest we got with any sub-input +}; + +template struct OutputType_; +template struct OutputType_> { typedef T Type; }; +template +using OutputType = typename OutputType_< +#if _MSC_VER + std::result_of_t + // The instance() based version below results in: + // C2064: term does not evaluate to a function taking 1 arguments +#else + decltype(instance()(instance())) +#endif + >::Type; +// Synonym for the output type of a parser, given the parser type and the input type. + +// ======================================================================================= + +template +class ParserRef { + // Acts as a reference to some other parser, with simplified type. The referenced parser + // is polymorphic by virtual call rather than templates. For grammars of non-trivial size, + // it is important to inject refs into the grammar here and there to prevent the parser types + // from becoming ridiculous. Using too many of them can hurt performance, though. + +public: + ParserRef(): parser(nullptr), wrapper(nullptr) {} + ParserRef(const ParserRef&) = default; + ParserRef(ParserRef&&) = default; + ParserRef& operator=(const ParserRef& other) = default; + ParserRef& operator=(ParserRef&& other) = default; + + template + constexpr ParserRef(Other&& other) + : parser(&other), wrapper(&WrapperImplInstance>::instance) { + static_assert(kj::isReference(), "ParserRef should not be assigned to a temporary."); + } + + template + inline ParserRef& operator=(Other&& other) { + static_assert(kj::isReference(), "ParserRef should not be assigned to a temporary."); + parser = &other; + wrapper = &WrapperImplInstance>::instance; + return *this; + } + + KJ_ALWAYS_INLINE(Maybe operator()(Input& input) const) { + // Always inline in the hopes that this allows branch prediction to kick in so the virtual call + // doesn't hurt so much. + return wrapper->parse(parser, input); + } + +private: + struct Wrapper { + virtual Maybe parse(const void* parser, Input& input) const = 0; + }; + template + struct WrapperImpl: public Wrapper { + Maybe parse(const void* parser, Input& input) const override { + return (*reinterpret_cast(parser))(input); + } + }; + template + struct WrapperImplInstance { +#if _MSC_VER + // TODO(msvc): MSVC currently fails to initialize vtable pointers for constexpr values so + // we have to make this just const instead. + static const WrapperImpl instance; +#else + static constexpr WrapperImpl instance = WrapperImpl(); +#endif + }; + + const void* parser; + const Wrapper* wrapper; +}; + +template +template +#if _MSC_VER +const typename ParserRef::template WrapperImpl +ParserRef::WrapperImplInstance::instance = WrapperImpl(); +#else +constexpr typename ParserRef::template WrapperImpl +ParserRef::WrapperImplInstance::instance; +#endif + +template +constexpr ParserRef> ref(ParserImpl& impl) { + // Constructs a ParserRef. You must specify the input type explicitly, e.g. + // `ref(myParser)`. + + return ParserRef>(impl); +} + +// ------------------------------------------------------------------- +// any +// Output = one token + +class Any_ { +public: + template + Maybe().consume())>> operator()(Input& input) const { + if (input.atEnd()) { + return nullptr; + } else { + return input.consume(); + } + } +}; + +constexpr Any_ any = Any_(); +// A parser which matches any token and simply returns it. + +// ------------------------------------------------------------------- +// exactly() +// Output = Tuple<> + +template +class Exactly_ { +public: + explicit constexpr Exactly_(T&& expected): expected(expected) {} + + template + Maybe> operator()(Input& input) const { + if (input.atEnd() || input.current() != expected) { + return nullptr; + } else { + input.next(); + return Tuple<>(); + } + } + +private: + T expected; +}; + +template +constexpr Exactly_ exactly(T&& expected) { + // Constructs a parser which succeeds when the input is exactly the token specified. The + // result is always the empty tuple. + + return Exactly_(kj::fwd(expected)); +} + +// ------------------------------------------------------------------- +// exactlyConst() +// Output = Tuple<> + +template +class ExactlyConst_ { +public: + explicit constexpr ExactlyConst_() {} + + template + Maybe> operator()(Input& input) const { + if (input.atEnd() || input.current() != expected) { + return nullptr; + } else { + input.next(); + return Tuple<>(); + } + } +}; + +template +constexpr ExactlyConst_ exactlyConst() { + // Constructs a parser which succeeds when the input is exactly the token specified. The + // result is always the empty tuple. This parser is templated on the token value which may cause + // it to perform better -- or worse. Be sure to measure. + + return ExactlyConst_(); +} + +// ------------------------------------------------------------------- +// constResult() + +template +class ConstResult_ { +public: + explicit constexpr ConstResult_(SubParser&& subParser, Result&& result) + : subParser(kj::fwd(subParser)), result(kj::fwd(result)) {} + + template + Maybe operator()(Input& input) const { + if (subParser(input) == nullptr) { + return nullptr; + } else { + return result; + } + } + +private: + SubParser subParser; + Result result; +}; + +template +constexpr ConstResult_ constResult(SubParser&& subParser, Result&& result) { + // Constructs a parser which returns exactly `result` if `subParser` is successful. + return ConstResult_(kj::fwd(subParser), kj::fwd(result)); +} + +template +constexpr ConstResult_> discard(SubParser&& subParser) { + // Constructs a parser which wraps `subParser` but discards the result. + return constResult(kj::fwd(subParser), Tuple<>()); +} + +// ------------------------------------------------------------------- +// sequence() +// Output = Flattened Tuple of outputs of sub-parsers. + +template class Sequence_; + +template +class Sequence_ { +public: + template + explicit constexpr Sequence_(T&& firstSubParser, U&&... rest) + : first(kj::fwd(firstSubParser)), rest(kj::fwd(rest)...) {} + + // TODO(msvc): The trailing return types on `operator()` and `parseNext()` expose at least two + // bugs in MSVC: + // + // 1. An ICE. + // 2. 'error C2672: 'operator __surrogate_func': no matching overloaded function found)', + // which crops up in numerous places when trying to build the capnp command line tools. + // + // The only workaround I found for both bugs is to omit the trailing return types and instead + // rely on C++14's return type deduction. + + template + auto operator()(Input& input) const +#ifndef _MSC_VER + -> Maybe>(), + instance>()...))> +#endif + { + return parseNext(input); + } + + template + auto parseNext(Input& input, InitialParams&&... initialParams) const +#ifndef _MSC_VER + -> Maybe(initialParams)..., + instance>(), + instance>()...))> +#endif + { + KJ_IF_MAYBE(firstResult, first(input)) { + return rest.parseNext(input, kj::fwd(initialParams)..., + kj::mv(*firstResult)); + } else { + // TODO(msvc): MSVC depends on return type deduction to compile this function, so we need to + // help it deduce the right type on this code path. + return Maybe(initialParams)..., + instance>(), + instance>()...))>{nullptr}; + } + } + +private: + FirstSubParser first; + Sequence_ rest; +}; + +template <> +class Sequence_<> { +public: + template + Maybe> operator()(Input& input) const { + return parseNext(input); + } + + template + auto parseNext(Input& input, Params&&... params) const -> + Maybe(params)...))> { + return tuple(kj::fwd(params)...); + } +}; + +template +constexpr Sequence_ sequence(SubParsers&&... subParsers) { + // Constructs a parser that executes each of the parameter parsers in sequence and returns a + // tuple of their results. + + return Sequence_(kj::fwd(subParsers)...); +} + +// ------------------------------------------------------------------- +// many() +// Output = Array of output of sub-parser, or just a uint count if the sub-parser returns Tuple<>. + +template +class Many_ { + template > + struct Impl; +public: + explicit constexpr Many_(SubParser&& subParser) + : subParser(kj::fwd(subParser)) {} + + template + auto operator()(Input& input) const + -> decltype(Impl::apply(instance(), input)); + +private: + SubParser subParser; +}; + +template +template +struct Many_::Impl { + static Maybe> apply(const SubParser& subParser, Input& input) { + typedef Vector> Results; + Results results; + + while (!input.atEnd()) { + Input subInput(input); + + KJ_IF_MAYBE(subResult, subParser(subInput)) { + subInput.advanceParent(); + results.add(kj::mv(*subResult)); + } else { + break; + } + } + + if (atLeastOne && results.empty()) { + return nullptr; + } + + return results.releaseAsArray(); + } +}; + +template +template +struct Many_::Impl> { + // If the sub-parser output is Tuple<>, just return a count. + + static Maybe apply(const SubParser& subParser, Input& input) { + uint count = 0; + + while (!input.atEnd()) { + Input subInput(input); + + KJ_IF_MAYBE(subResult, subParser(subInput)) { + subInput.advanceParent(); + ++count; + } else { + break; + } + } + + if (atLeastOne && count == 0) { + return nullptr; + } + + return count; + } +}; + +template +template +auto Many_::operator()(Input& input) const + -> decltype(Impl::apply(instance(), input)) { + return Impl>::apply(subParser, input); +} + +template +constexpr Many_ many(SubParser&& subParser) { + // Constructs a parser that repeatedly executes the given parser until it fails, returning an + // Array of the results (or a uint count if `subParser` returns an empty tuple). + return Many_(kj::fwd(subParser)); +} + +template +constexpr Many_ oneOrMore(SubParser&& subParser) { + // Like `many()` but the parser must parse at least one item to be successful. + return Many_(kj::fwd(subParser)); +} + +// ------------------------------------------------------------------- +// times() +// Output = Array of output of sub-parser, or Tuple<> if sub-parser returns Tuple<>. + +template +class Times_ { + template > + struct Impl; +public: + explicit constexpr Times_(SubParser&& subParser, uint count) + : subParser(kj::fwd(subParser)), count(count) {} + + template + auto operator()(Input& input) const + -> decltype(Impl::apply(instance(), instance(), input)); + +private: + SubParser subParser; + uint count; +}; + +template +template +struct Times_::Impl { + static Maybe> apply(const SubParser& subParser, uint count, Input& input) { + auto results = heapArrayBuilder>(count); + + while (results.size() < count) { + if (input.atEnd()) { + return nullptr; + } else KJ_IF_MAYBE(subResult, subParser(input)) { + results.add(kj::mv(*subResult)); + } else { + return nullptr; + } + } + + return results.finish(); + } +}; + +template +template +struct Times_::Impl> { + // If the sub-parser output is Tuple<>, just return a count. + + static Maybe> apply(const SubParser& subParser, uint count, Input& input) { + uint actualCount = 0; + + while (actualCount < count) { + if (input.atEnd()) { + return nullptr; + } else KJ_IF_MAYBE(subResult, subParser(input)) { + ++actualCount; + } else { + return nullptr; + } + } + + return tuple(); + } +}; + +template +template +auto Times_::operator()(Input& input) const + -> decltype(Impl::apply(instance(), instance(), input)) { + return Impl>::apply(subParser, count, input); +} + +template +constexpr Times_ times(SubParser&& subParser, uint count) { + // Constructs a parser that repeats the subParser exactly `count` times. + return Times_(kj::fwd(subParser), count); +} + +// ------------------------------------------------------------------- +// optional() +// Output = Maybe + +template +class Optional_ { +public: + explicit constexpr Optional_(SubParser&& subParser) + : subParser(kj::fwd(subParser)) {} + + template + Maybe>> operator()(Input& input) const { + typedef Maybe> Result; + + Input subInput(input); + KJ_IF_MAYBE(subResult, subParser(subInput)) { + subInput.advanceParent(); + return Result(kj::mv(*subResult)); + } else { + return Result(nullptr); + } + } + +private: + SubParser subParser; +}; + +template +constexpr Optional_ optional(SubParser&& subParser) { + // Constructs a parser that accepts zero or one of the given sub-parser, returning a Maybe + // of the sub-parser's result. + return Optional_(kj::fwd(subParser)); +} + +// ------------------------------------------------------------------- +// oneOf() +// All SubParsers must have same output type, which becomes the output type of the +// OneOfParser. + +template +class OneOf_; + +template +class OneOf_ { +public: + explicit constexpr OneOf_(FirstSubParser&& firstSubParser, SubParsers&&... rest) + : first(kj::fwd(firstSubParser)), rest(kj::fwd(rest)...) {} + + template + Maybe> operator()(Input& input) const { + { + Input subInput(input); + Maybe> firstResult = first(subInput); + + if (firstResult != nullptr) { + subInput.advanceParent(); + return kj::mv(firstResult); + } + } + + // Hoping for some tail recursion here... + return rest(input); + } + +private: + FirstSubParser first; + OneOf_ rest; +}; + +template <> +class OneOf_<> { +public: + template + decltype(nullptr) operator()(Input& input) const { + return nullptr; + } +}; + +template +constexpr OneOf_ oneOf(SubParsers&&... parsers) { + // Constructs a parser that accepts one of a set of options. The parser behaves as the first + // sub-parser in the list which returns successfully. All of the sub-parsers must return the + // same type. + return OneOf_(kj::fwd(parsers)...); +} + +// ------------------------------------------------------------------- +// transform() +// Output = Result of applying transform functor to input value. If input is a tuple, it is +// unpacked to form the transformation parameters. + +template +struct Span { +public: + inline const Position& begin() const { return begin_; } + inline const Position& end() const { return end_; } + + Span() = default; + inline constexpr Span(Position&& begin, Position&& end): begin_(mv(begin)), end_(mv(end)) {} + +private: + Position begin_; + Position end_; +}; + +template +constexpr Span> span(Position&& start, Position&& end) { + return Span>(kj::fwd(start), kj::fwd(end)); +} + +template +class Transform_ { +public: + explicit constexpr Transform_(SubParser&& subParser, TransformFunc&& transform) + : subParser(kj::fwd(subParser)), transform(kj::fwd(transform)) {} + + template + Maybe(), + instance&&>()))> + operator()(Input& input) const { + KJ_IF_MAYBE(subResult, subParser(input)) { + return kj::apply(transform, kj::mv(*subResult)); + } else { + return nullptr; + } + } + +private: + SubParser subParser; + TransformFunc transform; +}; + +template +class TransformOrReject_ { +public: + explicit constexpr TransformOrReject_(SubParser&& subParser, TransformFunc&& transform) + : subParser(kj::fwd(subParser)), transform(kj::fwd(transform)) {} + + template + decltype(kj::apply(instance(), instance&&>())) + operator()(Input& input) const { + KJ_IF_MAYBE(subResult, subParser(input)) { + return kj::apply(transform, kj::mv(*subResult)); + } else { + return nullptr; + } + } + +private: + SubParser subParser; + TransformFunc transform; +}; + +template +class TransformWithLocation_ { +public: + explicit constexpr TransformWithLocation_(SubParser&& subParser, TransformFunc&& transform) + : subParser(kj::fwd(subParser)), transform(kj::fwd(transform)) {} + + template + Maybe(), + instance().getPosition())>>>(), + instance&&>()))> + operator()(Input& input) const { + auto start = input.getPosition(); + KJ_IF_MAYBE(subResult, subParser(input)) { + return kj::apply(transform, Span(kj::mv(start), input.getPosition()), + kj::mv(*subResult)); + } else { + return nullptr; + } + } + +private: + SubParser subParser; + TransformFunc transform; +}; + +template +constexpr Transform_ transform( + SubParser&& subParser, TransformFunc&& functor) { + // Constructs a parser which executes some other parser and then transforms the result by invoking + // `functor` on it. Typically `functor` is a lambda. It is invoked using `kj::apply`, + // meaning tuples will be unpacked as arguments. + return Transform_( + kj::fwd(subParser), kj::fwd(functor)); +} + +template +constexpr TransformOrReject_ transformOrReject( + SubParser&& subParser, TransformFunc&& functor) { + // Like `transform()` except that `functor` returns a `Maybe`. If it returns null, parsing fails, + // otherwise the parser's result is the content of the `Maybe`. + return TransformOrReject_( + kj::fwd(subParser), kj::fwd(functor)); +} + +template +constexpr TransformWithLocation_ transformWithLocation( + SubParser&& subParser, TransformFunc&& functor) { + // Like `transform` except that `functor` also takes a `Span` as its first parameter specifying + // the location of the parsed content. The span's position type is whatever the parser input's + // getPosition() returns. + return TransformWithLocation_( + kj::fwd(subParser), kj::fwd(functor)); +} + +// ------------------------------------------------------------------- +// notLookingAt() +// Fails if the given parser succeeds at the current location. + +template +class NotLookingAt_ { +public: + explicit constexpr NotLookingAt_(SubParser&& subParser) + : subParser(kj::fwd(subParser)) {} + + template + Maybe> operator()(Input& input) const { + Input subInput(input); + subInput.forgetParent(); + if (subParser(subInput) == nullptr) { + return Tuple<>(); + } else { + return nullptr; + } + } + +private: + SubParser subParser; +}; + +template +constexpr NotLookingAt_ notLookingAt(SubParser&& subParser) { + // Constructs a parser which fails at any position where the given parser succeeds. Otherwise, + // it succeeds without consuming any input and returns an empty tuple. + return NotLookingAt_(kj::fwd(subParser)); +} + +// ------------------------------------------------------------------- +// endOfInput() +// Output = Tuple<>, only succeeds if at end-of-input + +class EndOfInput_ { +public: + template + Maybe> operator()(Input& input) const { + if (input.atEnd()) { + return Tuple<>(); + } else { + return nullptr; + } + } +}; + +constexpr EndOfInput_ endOfInput = EndOfInput_(); +// A parser that succeeds only if it is called with no input. + +} // namespace parse +} // namespace kj + +#endif // KJ_PARSE_COMMON_H_ diff --git a/phonelibs/capnp-cpp/include/kj/refcount.h b/phonelibs/capnp-cpp/include/kj/refcount.h new file mode 100644 index 00000000000000..a24e4bf5b95e7d --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/refcount.h @@ -0,0 +1,107 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#include "memory.h" + +#ifndef KJ_REFCOUNT_H_ +#define KJ_REFCOUNT_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +namespace kj { + +class Refcounted: private Disposer { + // Subclass this to create a class that contains a reference count. Then, use + // `kj::refcounted()` to allocate a new refcounted pointer. + // + // Do NOT use this lightly. Refcounting is a crutch. Good designs should strive to make object + // ownership clear, so that refcounting is not necessary. All that said, reference counting can + // sometimes simplify code that would otherwise become convoluted with explicit ownership, even + // when ownership relationships are clear at an abstract level. + // + // NOT THREADSAFE: This refcounting implementation assumes that an object's references are + // manipulated only in one thread, because atomic (thread-safe) refcounting is surprisingly slow. + // + // In general, abstract classes should _not_ subclass this. The concrete class at the bottom + // of the hierarchy should be the one to decide how it implements refcounting. Interfaces should + // expose only an `addRef()` method that returns `Own`. There are two reasons for + // this rule: + // 1. Interfaces would need to virtually inherit Refcounted, otherwise two refcounted interfaces + // could not be inherited by the same subclass. Virtual inheritance is awkward and + // inefficient. + // 2. An implementation may decide that it would rather return a copy than a refcount, or use + // some other strategy. + // + // TODO(cleanup): Rethink above. Virtual inheritance is not necessarily that bad. OTOH, a + // virtual function call for every refcount is sad in its own way. A Ref type to replace + // Own could also be nice. + +public: + virtual ~Refcounted() noexcept(false); + + inline bool isShared() const { return refcount > 1; } + // Check if there are multiple references to this object. This is sometimes useful for deciding + // whether it's safe to modify the object vs. make a copy. + +private: + mutable uint refcount = 0; + // "mutable" because disposeImpl() is const. Bleh. + + void disposeImpl(void* pointer) const override; + template + static Own addRefInternal(T* object); + + template + friend Own addRef(T& object); + template + friend Own refcounted(Params&&... params); +}; + +template +inline Own refcounted(Params&&... params) { + // Allocate a new refcounted instance of T, passing `params` to its constructor. Returns an + // initial reference to the object. More references can be created with `kj::addRef()`. + + return Refcounted::addRefInternal(new T(kj::fwd(params)...)); +} + +template +Own addRef(T& object) { + // Return a new reference to `object`, which must subclass Refcounted and have been allocated + // using `kj::refcounted<>()`. It is suggested that subclasses implement a non-static addRef() + // method which wraps this and returns the appropriate type. + + KJ_IREQUIRE(object.Refcounted::refcount > 0, "Object not allocated with kj::refcounted()."); + return Refcounted::addRefInternal(&object); +} + +template +Own Refcounted::addRefInternal(T* object) { + Refcounted* refcounted = object; + ++refcounted->refcount; + return Own(object, *refcounted); +} + +} // namespace kj + +#endif // KJ_REFCOUNT_H_ diff --git a/phonelibs/capnp-cpp/include/kj/std/iostream.h b/phonelibs/capnp-cpp/include/kj/std/iostream.h new file mode 100644 index 00000000000000..627e0fcf8622fe --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/std/iostream.h @@ -0,0 +1,88 @@ +// Copyright (c) 2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +/* + * Compatibility layer for stdlib iostream + */ + +#ifndef KJ_STD_IOSTREAM_H_ +#define KJ_STD_IOSTREAM_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "../io.h" +#include + +namespace kj { +namespace std { + +class StdOutputStream: public kj::OutputStream { + +public: + explicit StdOutputStream(::std::ostream& stream) : stream_(stream) {} + ~StdOutputStream() noexcept(false) {} + + virtual void write(const void* src, size_t size) override { + // Always writes the full size. + + stream_.write((char*)src, size); + } + + virtual void write(ArrayPtr> pieces) override { + // Equivalent to write()ing each byte array in sequence, which is what the + // default implementation does. Override if you can do something better, + // e.g. use writev() to do the write in a single syscall. + + for (auto piece : pieces) { + write(piece.begin(), piece.size()); + } + } + +private: + ::std::ostream& stream_; + +}; + +class StdInputStream: public kj::InputStream { + +public: + explicit StdInputStream(::std::istream& stream) : stream_(stream) {} + ~StdInputStream() noexcept(false) {} + + virtual size_t tryRead( + void* buffer, size_t minBytes, size_t maxBytes) override { + // Like read(), but may return fewer than minBytes on EOF. + + stream_.read((char*)buffer, maxBytes); + return stream_.gcount(); + } + +private: + ::std::istream& stream_; + +}; + +} // namespace std +} // namespace kj + +#endif // KJ_STD_IOSTREAM_H_ diff --git a/phonelibs/capnp-cpp/include/kj/string-tree.h b/phonelibs/capnp-cpp/include/kj/string-tree.h new file mode 100644 index 00000000000000..70a46319ef82a5 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/string-tree.h @@ -0,0 +1,212 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_STRING_TREE_H_ +#define KJ_STRING_TREE_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "string.h" + +namespace kj { + +class StringTree { + // A long string, represented internally as a tree of strings. This data structure is like a + // String, but optimized for concatenation and iteration at the expense of seek time. The + // structure is intended to be used for building large text blobs from many small pieces, where + // repeatedly concatenating smaller strings into larger ones would waste copies. This structure + // is NOT intended for use cases requiring random access or computing substrings. For those, + // you should use a Rope, which is a much more complicated data structure. + // + // The proper way to construct a StringTree is via kj::strTree(...), which works just like + // kj::str(...) but returns a StringTree rather than a String. + // + // KJ_STRINGIFY() functions that construct large strings from many smaller strings are encouraged + // to return StringTree rather than a flat char container. + +public: + inline StringTree(): size_(0) {} + inline StringTree(String&& text): size_(text.size()), text(kj::mv(text)) {} + + StringTree(Array&& pieces, StringPtr delim); + // Build a StringTree by concatenating the given pieces, delimited by the given delimiter + // (e.g. ", "). + + inline size_t size() const { return size_; } + + template + void visit(Func&& func) const; + + String flatten() const; + // Return the contents as a string. + + // TODO(someday): flatten() when *this is an rvalue and when branches.size() == 0 could simply + // return `kj::mv(text)`. Requires reference qualifiers (Clang 3.3 / GCC 4.8). + + void flattenTo(char* __restrict__ target) const; + // Copy the contents to the given character array. Does not add a NUL terminator. + +private: + size_t size_; + String text; + + struct Branch; + Array branches; // In order. + + inline void fill(char* pos, size_t branchIndex); + template + void fill(char* pos, size_t branchIndex, First&& first, Rest&&... rest); + template + void fill(char* pos, size_t branchIndex, StringTree&& first, Rest&&... rest); + template + void fill(char* pos, size_t branchIndex, Array&& first, Rest&&... rest); + template + void fill(char* pos, size_t branchIndex, String&& first, Rest&&... rest); + + template + static StringTree concat(Params&&... params); + static StringTree&& concat(StringTree&& param) { return kj::mv(param); } + + template + static inline size_t flatSize(const T& t) { return t.size(); } + static inline size_t flatSize(String&& s) { return 0; } + static inline size_t flatSize(StringTree&& s) { return 0; } + + template + static inline size_t branchCount(const T& t) { return 0; } + static inline size_t branchCount(String&& s) { return 1; } + static inline size_t branchCount(StringTree&& s) { return 1; } + + template + friend StringTree strTree(Params&&... params); +}; + +inline StringTree&& KJ_STRINGIFY(StringTree&& tree) { return kj::mv(tree); } +inline const StringTree& KJ_STRINGIFY(const StringTree& tree) { return tree; } + +inline StringTree KJ_STRINGIFY(Array&& trees) { return StringTree(kj::mv(trees), ""); } + +template +StringTree strTree(Params&&... params); +// Build a StringTree by stringifying the given parameters and concatenating the results. +// If any of the parameters stringify to StringTree rvalues, they will be incorporated as +// branches to avoid a copy. + +// ======================================================================================= +// Inline implementation details + +namespace _ { // private + +template +char* fill(char* __restrict__ target, const StringTree& first, Rest&&... rest) { + // Make str() work with stringifiers that return StringTree by patching fill(). + + first.flattenTo(target); + return fill(target + first.size(), kj::fwd(rest)...); +} + +template constexpr bool isStringTree() { return false; } +template <> constexpr bool isStringTree() { return true; } + +inline StringTree&& toStringTreeOrCharSequence(StringTree&& tree) { return kj::mv(tree); } +inline StringTree toStringTreeOrCharSequence(String&& str) { return StringTree(kj::mv(str)); } + +template +inline auto toStringTreeOrCharSequence(T&& value) + -> decltype(toCharSequence(kj::fwd(value))) { + static_assert(!isStringTree>(), + "When passing a StringTree into kj::strTree(), either pass it by rvalue " + "(use kj::mv(value)) or explicitly call value.flatten() to make a copy."); + + return toCharSequence(kj::fwd(value)); +} + +} // namespace _ (private) + +struct StringTree::Branch { + size_t index; + // Index in `text` where this branch should be inserted. + + StringTree content; +}; + +template +void StringTree::visit(Func&& func) const { + size_t pos = 0; + for (auto& branch: branches) { + if (branch.index > pos) { + func(text.slice(pos, branch.index)); + pos = branch.index; + } + branch.content.visit(func); + } + if (text.size() > pos) { + func(text.slice(pos, text.size())); + } +} + +inline void StringTree::fill(char* pos, size_t branchIndex) { + KJ_IREQUIRE(pos == text.end() && branchIndex == branches.size(), + kj::str(text.end() - pos, ' ', branches.size() - branchIndex).cStr()); +} + +template +void StringTree::fill(char* pos, size_t branchIndex, First&& first, Rest&&... rest) { + pos = _::fill(pos, kj::fwd(first)); + fill(pos, branchIndex, kj::fwd(rest)...); +} + +template +void StringTree::fill(char* pos, size_t branchIndex, StringTree&& first, Rest&&... rest) { + branches[branchIndex].index = pos - text.begin(); + branches[branchIndex].content = kj::mv(first); + fill(pos, branchIndex + 1, kj::fwd(rest)...); +} + +template +void StringTree::fill(char* pos, size_t branchIndex, String&& first, Rest&&... rest) { + branches[branchIndex].index = pos - text.begin(); + branches[branchIndex].content = StringTree(kj::mv(first)); + fill(pos, branchIndex + 1, kj::fwd(rest)...); +} + +template +StringTree StringTree::concat(Params&&... params) { + StringTree result; + result.size_ = _::sum({params.size()...}); + result.text = heapString( + _::sum({StringTree::flatSize(kj::fwd(params))...})); + result.branches = heapArray( + _::sum({StringTree::branchCount(kj::fwd(params))...})); + result.fill(result.text.begin(), 0, kj::fwd(params)...); + return result; +} + +template +StringTree strTree(Params&&... params) { + return StringTree::concat(_::toStringTreeOrCharSequence(kj::fwd(params))...); +} + +} // namespace kj + +#endif // KJ_STRING_TREE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/string.h b/phonelibs/capnp-cpp/include/kj/string.h new file mode 100644 index 00000000000000..9048be24170e5b --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/string.h @@ -0,0 +1,534 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_STRING_H_ +#define KJ_STRING_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include +#include "array.h" +#include + +namespace kj { + +class StringPtr; +class String; + +class StringTree; // string-tree.h + +// Our STL string SFINAE trick does not work with GCC 4.7, but it works with Clang and GCC 4.8, so +// we'll just preprocess it out if not supported. +#if __clang__ || __GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) || _MSC_VER +#define KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP 1 +#endif + +// ======================================================================================= +// StringPtr -- A NUL-terminated ArrayPtr containing UTF-8 text. +// +// NUL bytes are allowed to appear before the end of the string. The only requirement is that +// a NUL byte appear immediately after the last byte of the content. This terminator byte is not +// counted in the string's size. + +class StringPtr { +public: + inline StringPtr(): content("", 1) {} + inline StringPtr(decltype(nullptr)): content("", 1) {} + inline StringPtr(const char* value): content(value, strlen(value) + 1) {} + inline StringPtr(const char* value, size_t size): content(value, size + 1) { + KJ_IREQUIRE(value[size] == '\0', "StringPtr must be NUL-terminated."); + } + inline StringPtr(const char* begin, const char* end): StringPtr(begin, end - begin) {} + inline StringPtr(const String& value); + +#if KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP + template ().c_str())> + inline StringPtr(const T& t): StringPtr(t.c_str()) {} + // Allow implicit conversion from any class that has a c_str() method (namely, std::string). + // We use a template trick to detect std::string in order to avoid including the header for + // those who don't want it. + + template ().c_str())> + inline operator T() const { return cStr(); } + // Allow implicit conversion to any class that has a c_str() method (namely, std::string). + // We use a template trick to detect std::string in order to avoid including the header for + // those who don't want it. +#endif + + inline operator ArrayPtr() const; + inline ArrayPtr asArray() const; + inline ArrayPtr asBytes() const { return asArray().asBytes(); } + // Result does not include NUL terminator. + + inline const char* cStr() const { return content.begin(); } + // Returns NUL-terminated string. + + inline size_t size() const { return content.size() - 1; } + // Result does not include NUL terminator. + + inline char operator[](size_t index) const { return content[index]; } + + inline const char* begin() const { return content.begin(); } + inline const char* end() const { return content.end() - 1; } + + inline bool operator==(decltype(nullptr)) const { return content.size() <= 1; } + inline bool operator!=(decltype(nullptr)) const { return content.size() > 1; } + + inline bool operator==(const StringPtr& other) const; + inline bool operator!=(const StringPtr& other) const { return !(*this == other); } + inline bool operator< (const StringPtr& other) const; + inline bool operator> (const StringPtr& other) const { return other < *this; } + inline bool operator<=(const StringPtr& other) const { return !(other < *this); } + inline bool operator>=(const StringPtr& other) const { return !(*this < other); } + + inline StringPtr slice(size_t start) const; + inline ArrayPtr slice(size_t start, size_t end) const; + // A string slice is only NUL-terminated if it is a suffix, so slice() has a one-parameter + // version that assumes end = size(). + + inline bool startsWith(const StringPtr& other) const; + inline bool endsWith(const StringPtr& other) const; + + inline Maybe findFirst(char c) const; + inline Maybe findLast(char c) const; + + template + T parseAs() const; + // Parse string as template number type. + // Integer numbers prefixed by "0x" and "0X" are parsed in base 16 (like strtoi with base 0). + // Integer numbers prefixed by "0" are parsed in base 10 (unlike strtoi with base 0). + // Overflowed integer numbers throw exception. + // Overflowed floating numbers return inf. + +private: + inline StringPtr(ArrayPtr content): content(content) {} + + ArrayPtr content; +}; + +inline bool operator==(const char* a, const StringPtr& b) { return b == a; } +inline bool operator!=(const char* a, const StringPtr& b) { return b != a; } + +template <> char StringPtr::parseAs() const; +template <> signed char StringPtr::parseAs() const; +template <> unsigned char StringPtr::parseAs() const; +template <> short StringPtr::parseAs() const; +template <> unsigned short StringPtr::parseAs() const; +template <> int StringPtr::parseAs() const; +template <> unsigned StringPtr::parseAs() const; +template <> long StringPtr::parseAs() const; +template <> unsigned long StringPtr::parseAs() const; +template <> long long StringPtr::parseAs() const; +template <> unsigned long long StringPtr::parseAs() const; +template <> float StringPtr::parseAs() const; +template <> double StringPtr::parseAs() const; + +// ======================================================================================= +// String -- A NUL-terminated Array containing UTF-8 text. +// +// NUL bytes are allowed to appear before the end of the string. The only requirement is that +// a NUL byte appear immediately after the last byte of the content. This terminator byte is not +// counted in the string's size. +// +// To allocate a String, you must call kj::heapString(). We do not implement implicit copying to +// the heap because this hides potential inefficiency from the developer. + +class String { +public: + String() = default; + inline String(decltype(nullptr)): content(nullptr) {} + inline String(char* value, size_t size, const ArrayDisposer& disposer); + // Does not copy. `size` does not include NUL terminator, but `value` must be NUL-terminated. + inline explicit String(Array buffer); + // Does not copy. Requires `buffer` ends with `\0`. + + inline operator ArrayPtr(); + inline operator ArrayPtr() const; + inline ArrayPtr asArray(); + inline ArrayPtr asArray() const; + inline ArrayPtr asBytes() { return asArray().asBytes(); } + inline ArrayPtr asBytes() const { return asArray().asBytes(); } + // Result does not include NUL terminator. + + inline Array releaseArray() { return kj::mv(content); } + // Disowns the backing array (which includes the NUL terminator) and returns it. The String value + // is clobbered (as if moved away). + + inline const char* cStr() const; + + inline size_t size() const; + // Result does not include NUL terminator. + + inline char operator[](size_t index) const; + inline char& operator[](size_t index); + + inline char* begin(); + inline char* end(); + inline const char* begin() const; + inline const char* end() const; + + inline bool operator==(decltype(nullptr)) const { return content.size() <= 1; } + inline bool operator!=(decltype(nullptr)) const { return content.size() > 1; } + + inline bool operator==(const StringPtr& other) const { return StringPtr(*this) == other; } + inline bool operator!=(const StringPtr& other) const { return StringPtr(*this) != other; } + inline bool operator< (const StringPtr& other) const { return StringPtr(*this) < other; } + inline bool operator> (const StringPtr& other) const { return StringPtr(*this) > other; } + inline bool operator<=(const StringPtr& other) const { return StringPtr(*this) <= other; } + inline bool operator>=(const StringPtr& other) const { return StringPtr(*this) >= other; } + + inline bool startsWith(const StringPtr& other) const { return StringPtr(*this).startsWith(other);} + inline bool endsWith(const StringPtr& other) const { return StringPtr(*this).endsWith(other); } + + inline StringPtr slice(size_t start) const { return StringPtr(*this).slice(start); } + inline ArrayPtr slice(size_t start, size_t end) const { + return StringPtr(*this).slice(start, end); + } + + inline Maybe findFirst(char c) const { return StringPtr(*this).findFirst(c); } + inline Maybe findLast(char c) const { return StringPtr(*this).findLast(c); } + + template + T parseAs() const { return StringPtr(*this).parseAs(); } + // Parse as number + +private: + Array content; +}; + +inline bool operator==(const char* a, const String& b) { return b == a; } +inline bool operator!=(const char* a, const String& b) { return b != a; } + +String heapString(size_t size); +// Allocate a String of the given size on the heap, not including NUL terminator. The NUL +// terminator will be initialized automatically but the rest of the content is not initialized. + +String heapString(const char* value); +String heapString(const char* value, size_t size); +String heapString(StringPtr value); +String heapString(const String& value); +String heapString(ArrayPtr value); +// Allocates a copy of the given value on the heap. + +// ======================================================================================= +// Magic str() function which transforms parameters to text and concatenates them into one big +// String. + +namespace _ { // private + +inline size_t sum(std::initializer_list nums) { + size_t result = 0; + for (auto num: nums) { + result += num; + } + return result; +} + +inline char* fill(char* ptr) { return ptr; } + +template +char* fill(char* __restrict__ target, const StringTree& first, Rest&&... rest); +// Make str() work with stringifiers that return StringTree by patching fill(). +// +// Defined in string-tree.h. + +template +char* fill(char* __restrict__ target, const First& first, Rest&&... rest) { + auto i = first.begin(); + auto end = first.end(); + while (i != end) { + *target++ = *i++; + } + return fill(target, kj::fwd(rest)...); +} + +template +String concat(Params&&... params) { + // Concatenate a bunch of containers into a single Array. The containers can be anything that + // is iterable and whose elements can be converted to `char`. + + String result = heapString(sum({params.size()...})); + fill(result.begin(), kj::fwd(params)...); + return result; +} + +inline String concat(String&& arr) { + return kj::mv(arr); +} + +struct Stringifier { + // This is a dummy type with only one instance: STR (below). To make an arbitrary type + // stringifiable, define `operator*(Stringifier, T)` to return an iterable container of `char`. + // The container type must have a `size()` method. Be sure to declare the operator in the same + // namespace as `T` **or** in the global scope. + // + // A more usual way to accomplish what we're doing here would be to require that you define + // a function like `toString(T)` and then rely on argument-dependent lookup. However, this has + // the problem that it pollutes other people's namespaces and even the global namespace. For + // example, some other project may already have functions called `toString` which do something + // different. Declaring `operator*` with `Stringifier` as the left operand cannot conflict with + // anything. + + inline ArrayPtr operator*(ArrayPtr s) const { return s; } + inline ArrayPtr operator*(ArrayPtr s) const { return s; } + inline ArrayPtr operator*(const Array& s) const { return s; } + inline ArrayPtr operator*(const Array& s) const { return s; } + template + inline ArrayPtr operator*(const CappedArray& s) const { return s; } + template + inline ArrayPtr operator*(const FixedArray& s) const { return s; } + inline ArrayPtr operator*(const char* s) const { return arrayPtr(s, strlen(s)); } + inline ArrayPtr operator*(const String& s) const { return s.asArray(); } + inline ArrayPtr operator*(const StringPtr& s) const { return s.asArray(); } + + inline Range operator*(const Range& r) const { return r; } + inline Repeat operator*(const Repeat& r) const { return r; } + + inline FixedArray operator*(char c) const { + FixedArray result; + result[0] = c; + return result; + } + + StringPtr operator*(decltype(nullptr)) const; + StringPtr operator*(bool b) const; + + CappedArray operator*(signed char i) const; + CappedArray operator*(unsigned char i) const; + CappedArray operator*(short i) const; + CappedArray operator*(unsigned short i) const; + CappedArray operator*(int i) const; + CappedArray operator*(unsigned int i) const; + CappedArray operator*(long i) const; + CappedArray operator*(unsigned long i) const; + CappedArray operator*(long long i) const; + CappedArray operator*(unsigned long long i) const; + CappedArray operator*(float f) const; + CappedArray operator*(double f) const; + CappedArray operator*(const void* s) const; + + template + String operator*(ArrayPtr arr) const; + template + String operator*(const Array& arr) const; + +#if KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP // supports expression SFINAE? + template ().toString())> + inline Result operator*(T&& value) const { return kj::fwd(value).toString(); } +#endif +}; +static KJ_CONSTEXPR(const) Stringifier STR = Stringifier(); + +} // namespace _ (private) + +template +auto toCharSequence(T&& value) -> decltype(_::STR * kj::fwd(value)) { + // Returns an iterable of chars that represent a textual representation of the value, suitable + // for debugging. + // + // Most users should use str() instead, but toCharSequence() may occasionally be useful to avoid + // heap allocation overhead that str() implies. + // + // To specialize this function for your type, see KJ_STRINGIFY. + + return _::STR * kj::fwd(value); +} + +CappedArray hex(unsigned char i); +CappedArray hex(unsigned short i); +CappedArray hex(unsigned int i); +CappedArray hex(unsigned long i); +CappedArray hex(unsigned long long i); + +template +String str(Params&&... params) { + // Magic function which builds a string from a bunch of arbitrary values. Example: + // str(1, " / ", 2, " = ", 0.5) + // returns: + // "1 / 2 = 0.5" + // To teach `str` how to stringify a type, see `Stringifier`. + + return _::concat(toCharSequence(kj::fwd(params))...); +} + +inline String str(String&& s) { return mv(s); } +// Overload to prevent redundant allocation. + +template +String strArray(T&& arr, const char* delim) { + size_t delimLen = strlen(delim); + KJ_STACK_ARRAY(decltype(_::STR * arr[0]), pieces, kj::size(arr), 8, 32); + size_t size = 0; + for (size_t i = 0; i < kj::size(arr); i++) { + if (i > 0) size += delimLen; + pieces[i] = _::STR * arr[i]; + size += pieces[i].size(); + } + + String result = heapString(size); + char* pos = result.begin(); + for (size_t i = 0; i < kj::size(arr); i++) { + if (i > 0) { + memcpy(pos, delim, delimLen); + pos += delimLen; + } + pos = _::fill(pos, pieces[i]); + } + return result; +} + +namespace _ { // private + +template +inline String Stringifier::operator*(ArrayPtr arr) const { + return strArray(arr, ", "); +} + +template +inline String Stringifier::operator*(const Array& arr) const { + return strArray(arr, ", "); +} + +} // namespace _ (private) + +#define KJ_STRINGIFY(...) operator*(::kj::_::Stringifier, __VA_ARGS__) +// Defines a stringifier for a custom type. Example: +// +// class Foo {...}; +// inline StringPtr KJ_STRINGIFY(const Foo& foo) { return foo.name(); } +// +// This allows Foo to be passed to str(). +// +// The function should be declared either in the same namespace as the target type or in the global +// namespace. It can return any type which is an iterable container of chars. + +// ======================================================================================= +// Inline implementation details. + +inline StringPtr::StringPtr(const String& value): content(value.begin(), value.size() + 1) {} + +inline StringPtr::operator ArrayPtr() const { + return content.slice(0, content.size() - 1); +} + +inline ArrayPtr StringPtr::asArray() const { + return content.slice(0, content.size() - 1); +} + +inline bool StringPtr::operator==(const StringPtr& other) const { + return content.size() == other.content.size() && + memcmp(content.begin(), other.content.begin(), content.size() - 1) == 0; +} + +inline bool StringPtr::operator<(const StringPtr& other) const { + bool shorter = content.size() < other.content.size(); + int cmp = memcmp(content.begin(), other.content.begin(), + shorter ? content.size() : other.content.size()); + return cmp < 0 || (cmp == 0 && shorter); +} + +inline StringPtr StringPtr::slice(size_t start) const { + return StringPtr(content.slice(start, content.size())); +} +inline ArrayPtr StringPtr::slice(size_t start, size_t end) const { + return content.slice(start, end); +} + +inline bool StringPtr::startsWith(const StringPtr& other) const { + return other.content.size() <= content.size() && + memcmp(content.begin(), other.content.begin(), other.size()) == 0; +} +inline bool StringPtr::endsWith(const StringPtr& other) const { + return other.content.size() <= content.size() && + memcmp(end() - other.size(), other.content.begin(), other.size()) == 0; +} + +inline Maybe StringPtr::findFirst(char c) const { + const char* pos = reinterpret_cast(memchr(content.begin(), c, size())); + if (pos == nullptr) { + return nullptr; + } else { + return pos - content.begin(); + } +} + +inline Maybe StringPtr::findLast(char c) const { + for (size_t i = size(); i > 0; --i) { + if (content[i-1] == c) { + return i-1; + } + } + return nullptr; +} + +inline String::operator ArrayPtr() { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} +inline String::operator ArrayPtr() const { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} + +inline ArrayPtr String::asArray() { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} +inline ArrayPtr String::asArray() const { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} + +inline const char* String::cStr() const { return content == nullptr ? "" : content.begin(); } + +inline size_t String::size() const { return content == nullptr ? 0 : content.size() - 1; } + +inline char String::operator[](size_t index) const { return content[index]; } +inline char& String::operator[](size_t index) { return content[index]; } + +inline char* String::begin() { return content == nullptr ? nullptr : content.begin(); } +inline char* String::end() { return content == nullptr ? nullptr : content.end() - 1; } +inline const char* String::begin() const { return content == nullptr ? nullptr : content.begin(); } +inline const char* String::end() const { return content == nullptr ? nullptr : content.end() - 1; } + +inline String::String(char* value, size_t size, const ArrayDisposer& disposer) + : content(value, size + 1, disposer) { + KJ_IREQUIRE(value[size] == '\0', "String must be NUL-terminated."); +} + +inline String::String(Array buffer): content(kj::mv(buffer)) { + KJ_IREQUIRE(content.size() > 0 && content.back() == '\0', "String must be NUL-terminated."); +} + +inline String heapString(const char* value) { + return heapString(value, strlen(value)); +} +inline String heapString(StringPtr value) { + return heapString(value.begin(), value.size()); +} +inline String heapString(const String& value) { + return heapString(value.begin(), value.size()); +} +inline String heapString(ArrayPtr value) { + return heapString(value.begin(), value.size()); +} + +} // namespace kj + +#endif // KJ_STRING_H_ diff --git a/phonelibs/capnp-cpp/include/kj/test.h b/phonelibs/capnp-cpp/include/kj/test.h new file mode 100644 index 00000000000000..69e1c80840b85d --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/test.h @@ -0,0 +1,167 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_TEST_H_ +#define KJ_TEST_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "debug.h" +#include "vector.h" +#include "function.h" + +namespace kj { + +class TestRunner; + +class TestCase { +public: + TestCase(const char* file, uint line, const char* description); + ~TestCase(); + + virtual void run() = 0; + +private: + const char* file; + uint line; + const char* description; + TestCase* next; + TestCase** prev; + bool matchedFilter; + + friend class TestRunner; +}; + +#define KJ_TEST(description) \ + /* Make sure the linker fails if tests are not in anonymous namespaces. */ \ + extern int KJ_CONCAT(YouMustWrapTestsInAnonymousNamespace, __COUNTER__) KJ_UNUSED; \ + class KJ_UNIQUE_NAME(TestCase): public ::kj::TestCase { \ + public: \ + KJ_UNIQUE_NAME(TestCase)(): ::kj::TestCase(__FILE__, __LINE__, description) {} \ + void run() override; \ + } KJ_UNIQUE_NAME(testCase); \ + void KJ_UNIQUE_NAME(TestCase)::run() + +#if _MSC_VER +#define KJ_INDIRECT_EXPAND(m, vargs) m vargs +#define KJ_FAIL_EXPECT(...) \ + KJ_INDIRECT_EXPAND(KJ_LOG, (ERROR , __VA_ARGS__)); +#define KJ_EXPECT(cond, ...) \ + if (cond); else KJ_INDIRECT_EXPAND(KJ_FAIL_EXPECT, ("failed: expected " #cond , __VA_ARGS__)) +#else +#define KJ_FAIL_EXPECT(...) \ + KJ_LOG(ERROR, ##__VA_ARGS__); +#define KJ_EXPECT(cond, ...) \ + if (cond); else KJ_FAIL_EXPECT("failed: expected " #cond, ##__VA_ARGS__) +#endif + +#define KJ_EXPECT_THROW_RECOVERABLE(type, code) \ + do { \ + KJ_IF_MAYBE(e, ::kj::runCatchingExceptions([&]() { code; })) { \ + KJ_EXPECT(e->getType() == ::kj::Exception::Type::type, \ + "code threw wrong exception type: " #code, e->getType()); \ + } else { \ + KJ_FAIL_EXPECT("code did not throw: " #code); \ + } \ + } while (false) + +#define KJ_EXPECT_THROW_RECOVERABLE_MESSAGE(message, code) \ + do { \ + KJ_IF_MAYBE(e, ::kj::runCatchingExceptions([&]() { code; })) { \ + KJ_EXPECT(::kj::_::hasSubstring(e->getDescription(), message), \ + "exception description didn't contain expected substring", e->getDescription()); \ + } else { \ + KJ_FAIL_EXPECT("code did not throw: " #code); \ + } \ + } while (false) + +#if KJ_NO_EXCEPTIONS +#define KJ_EXPECT_THROW(type, code) \ + do { \ + KJ_EXPECT(::kj::_::expectFatalThrow(type, nullptr, [&]() { code; })); \ + } while (false) +#define KJ_EXPECT_THROW_MESSAGE(message, code) \ + do { \ + KJ_EXPECT(::kj::_::expectFatalThrow(nullptr, kj::StringPtr(message), [&]() { code; })); \ + } while (false) +#else +#define KJ_EXPECT_THROW KJ_EXPECT_THROW_RECOVERABLE +#define KJ_EXPECT_THROW_MESSAGE KJ_EXPECT_THROW_RECOVERABLE_MESSAGE +#endif + +#define KJ_EXPECT_LOG(level, substring) \ + ::kj::_::LogExpectation KJ_UNIQUE_NAME(_kjLogExpectation)(::kj::LogSeverity::level, substring) +// Expects that a log message with the given level and substring text will be printed within +// the current scope. This message will not cause the test to fail, even if it is an error. + +// ======================================================================================= + +namespace _ { // private + +bool hasSubstring(kj::StringPtr haystack, kj::StringPtr needle); + +#if KJ_NO_EXCEPTIONS +bool expectFatalThrow(Maybe type, Maybe message, + Function code); +// Expects that the given code will throw a fatal exception matching the given type and/or message. +// Since exceptions are disabled, the test will fork() and run in a subprocess. On Windows, where +// fork() is not available, this always returns true. +#endif + +class LogExpectation: public ExceptionCallback { +public: + LogExpectation(LogSeverity severity, StringPtr substring); + ~LogExpectation(); + + void logMessage(LogSeverity severity, const char* file, int line, int contextDepth, + String&& text) override; + +private: + LogSeverity severity; + StringPtr substring; + bool seen; + UnwindDetector unwindDetector; +}; + +class GlobFilter { + // Implements glob filters for the --filter flag. + // + // Exposed in header only for testing. + +public: + explicit GlobFilter(const char* pattern); + explicit GlobFilter(ArrayPtr pattern); + + bool matches(StringPtr name); + +private: + String pattern; + Vector states; + + void applyState(char c, int state); +}; + +} // namespace _ (private) +} // namespace kj + +#endif // KJ_TEST_H_ diff --git a/phonelibs/capnp-cpp/include/kj/thread.h b/phonelibs/capnp-cpp/include/kj/thread.h new file mode 100644 index 00000000000000..b17b88c520a2d8 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/thread.h @@ -0,0 +1,82 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_THREAD_H_ +#define KJ_THREAD_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include "function.h" +#include "exception.h" + +namespace kj { + +class Thread { + // A thread! Pass a lambda to the constructor, and it runs in the thread. The destructor joins + // the thread. If the function throws an exception, it is rethrown from the thread's destructor + // (if not unwinding from another exception). + +public: + explicit Thread(Function func); + KJ_DISALLOW_COPY(Thread); + + ~Thread() noexcept(false); + +#if !_WIN32 + void sendSignal(int signo); + // Send a Unix signal to the given thread, using pthread_kill or an equivalent. +#endif + + void detach(); + // Don't join the thread in ~Thread(). + +private: + struct ThreadState { + Function func; + kj::Maybe exception; + + unsigned int refcount; + // Owned by the parent thread and the child thread. + + void unref(); + }; + ThreadState* state; + +#if _WIN32 + void* threadHandle; +#else + unsigned long long threadId; // actually pthread_t +#endif + bool detached = false; + +#if _WIN32 + static unsigned long __stdcall runThread(void* ptr); +#else + static void* runThread(void* ptr); +#endif +}; + +} // namespace kj + +#endif // KJ_THREAD_H_ diff --git a/phonelibs/capnp-cpp/include/kj/threadlocal.h b/phonelibs/capnp-cpp/include/kj/threadlocal.h new file mode 100644 index 00000000000000..67d0db60ef7d6c --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/threadlocal.h @@ -0,0 +1,136 @@ +// Copyright (c) 2014, Jason Choy +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_THREADLOCAL_H_ +#define KJ_THREADLOCAL_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif +// This file declares a macro `KJ_THREADLOCAL_PTR` for declaring thread-local pointer-typed +// variables. Use like: +// KJ_THREADLOCAL_PTR(MyType) foo = nullptr; +// This is equivalent to: +// thread_local MyType* foo = nullptr; +// This can only be used at the global scope. +// +// AVOID USING THIS. Use of thread-locals is discouraged because they often have many of the same +// properties as singletons: http://www.object-oriented-security.org/lets-argue/singletons +// +// Also, thread-locals tend to be hostile to event-driven code, which can be particularly +// surprising when using fibers (all fibers in the same thread will share the same threadlocals, +// even though they do not share a stack). +// +// That said, thread-locals are sometimes needed for runtime logistics in the KJ framework. For +// example, the current exception callback and current EventLoop are stored as thread-local +// pointers. Since KJ only ever needs to store pointers, not values, we avoid the question of +// whether these values' destructors need to be run, and we avoid the need for heap allocation. + +#include "common.h" + +#if !defined(KJ_USE_PTHREAD_THREADLOCAL) && defined(__APPLE__) +#include "TargetConditionals.h" +#if TARGET_OS_IPHONE +// iOS apparently does not support __thread (nor C++11 thread_local). +#define KJ_USE_PTHREAD_TLS 1 +#endif +#endif + +#if KJ_USE_PTHREAD_TLS +#include +#endif + +namespace kj { + +#if KJ_USE_PTHREAD_TLS +// If __thread is unavailable, we'll fall back to pthreads. + +#define KJ_THREADLOCAL_PTR(type) \ + namespace { struct KJ_UNIQUE_NAME(_kj_TlpTag); } \ + static ::kj::_::ThreadLocalPtr< type, KJ_UNIQUE_NAME(_kj_TlpTag)> +// Hack: In order to ensure each thread-local results in a unique template instance, we declare +// a one-off dummy type to use as the second type parameter. + +namespace _ { // private + +template +class ThreadLocalPtr { + // Hacky type to emulate __thread T*. We need a separate instance of the ThreadLocalPtr template + // for every thread-local variable, because we don't want to require a global constructor, and in + // order to initialize the TLS on first use we need to use a local static variable (in getKey()). + // Each template instance will get a separate such local static variable, fulfilling our need. + +public: + ThreadLocalPtr() = default; + constexpr ThreadLocalPtr(decltype(nullptr)) {} + // Allow initialization to nullptr without a global constructor. + + inline ThreadLocalPtr& operator=(T* val) { + pthread_setspecific(getKey(), val); + return *this; + } + + inline operator T*() const { + return get(); + } + + inline T& operator*() const { + return *get(); + } + + inline T* operator->() const { + return get(); + } + +private: + inline T* get() const { + return reinterpret_cast(pthread_getspecific(getKey())); + } + + inline static pthread_key_t getKey() { + static pthread_key_t key = createKey(); + return key; + } + + static pthread_key_t createKey() { + pthread_key_t key; + pthread_key_create(&key, 0); + return key; + } +}; + +} // namespace _ (private) + +#elif __GNUC__ + +#define KJ_THREADLOCAL_PTR(type) static __thread type* +// GCC's __thread is lighter-weight than thread_local and is good enough for our purposes. + +#else + +#define KJ_THREADLOCAL_PTR(type) static thread_local type* + +#endif // KJ_USE_PTHREAD_TLS + +} // namespace kj + +#endif // KJ_THREADLOCAL_H_ diff --git a/phonelibs/capnp-cpp/include/kj/time.h b/phonelibs/capnp-cpp/include/kj/time.h new file mode 100644 index 00000000000000..37d7b8a90eea91 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/time.h @@ -0,0 +1,174 @@ +// Copyright (c) 2014 Google Inc. (contributed by Remy Blank ) +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_TIME_H_ +#define KJ_TIME_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async.h" +#include "units.h" +#include + +namespace kj { +namespace _ { // private + +class NanosecondLabel; +class TimeLabel; +class DateLabel; + +} // namespace _ (private) + +using Duration = Quantity; +// A time value, in nanoseconds. + +constexpr Duration NANOSECONDS = unit(); +constexpr Duration MICROSECONDS = 1000 * NANOSECONDS; +constexpr Duration MILLISECONDS = 1000 * MICROSECONDS; +constexpr Duration SECONDS = 1000 * MILLISECONDS; +constexpr Duration MINUTES = 60 * SECONDS; +constexpr Duration HOURS = 60 * MINUTES; +constexpr Duration DAYS = 24 * HOURS; + +using TimePoint = Absolute; +// An absolute time measured by some particular instance of `Timer`. `Time`s from two different +// `Timer`s may be measured from different origins and so are not necessarily compatible. + +using Date = Absolute; +// A point in real-world time, measured relative to the Unix epoch (Jan 1, 1970 00:00:00 UTC). + +constexpr Date UNIX_EPOCH = origin(); +// The `Date` representing Jan 1, 1970 00:00:00 UTC. + +class Clock { + // Interface to read the current date and time. +public: + virtual Date now() = 0; +}; + +Clock& nullClock(); +// A clock which always returns UNIX_EPOCH as the current time. Useful when you don't care about +// time. + +class Timer { + // Interface to time and timer functionality. + // + // Each `Timer` may have a different origin, and some `Timer`s may in fact tick at a different + // rate than real time (e.g. a `Timer` could represent CPU time consumed by a thread). However, + // all `Timer`s are monotonic: time will never appear to move backwards, even if the calendar + // date as tracked by the system is manually modified. + +public: + virtual TimePoint now() = 0; + // Returns the current value of a clock that moves steadily forward, independent of any + // changes in the wall clock. The value is updated every time the event loop waits, + // and is constant in-between waits. + + virtual Promise atTime(TimePoint time) = 0; + // Returns a promise that returns as soon as now() >= time. + + virtual Promise afterDelay(Duration delay) = 0; + // Equivalent to atTime(now() + delay). + + template + Promise timeoutAt(TimePoint time, Promise&& promise) KJ_WARN_UNUSED_RESULT; + // Return a promise equivalent to `promise` but which throws an exception (and cancels the + // original promise) if it hasn't completed by `time`. The thrown exception is of type + // "OVERLOADED". + + template + Promise timeoutAfter(Duration delay, Promise&& promise) KJ_WARN_UNUSED_RESULT; + // Return a promise equivalent to `promise` but which throws an exception (and cancels the + // original promise) if it hasn't completed after `delay` from now. The thrown exception is of + // type "OVERLOADED". + +private: + static kj::Exception makeTimeoutException(); +}; + +class TimerImpl final: public Timer { + // Implementation of Timer that expects an external caller -- usually, the EventPort + // implementation -- to tell it when time has advanced. + +public: + TimerImpl(TimePoint startTime); + ~TimerImpl() noexcept(false); + + Maybe nextEvent(); + // Returns the time at which the next scheduled timer event will occur, or null if no timer + // events are scheduled. + + Maybe timeoutToNextEvent(TimePoint start, Duration unit, uint64_t max); + // Convenience method which computes a timeout value to pass to an event-waiting system call to + // cause it to time out when the next timer event occurs. + // + // `start` is the time at which the timeout starts counting. This is typically not the same as + // now() since some time may have passed since the last time advanceTo() was called. + // + // `unit` is the time unit in which the timeout is measured. This is often MILLISECONDS. Note + // that this method will fractional values *up*, to guarantee that the returned timeout waits + // until just *after* the time the event is scheduled. + // + // The timeout will be clamped to `max`. Use this to avoid an overflow if e.g. the OS wants a + // 32-bit value or a signed value. + // + // Returns nullptr if there are no future events. + + void advanceTo(TimePoint newTime); + // Set the time to `time` and fire any at() events that have been passed. + + // implements Timer ---------------------------------------------------------- + TimePoint now() override; + Promise atTime(TimePoint time) override; + Promise afterDelay(Duration delay) override; + +private: + struct Impl; + class TimerPromiseAdapter; + TimePoint time; + Own impl; +}; + +// ======================================================================================= +// inline implementation details + +template +Promise Timer::timeoutAt(TimePoint time, Promise&& promise) { + return promise.exclusiveJoin(atTime(time).then([]() -> kj::Promise { + return makeTimeoutException(); + })); +} + +template +Promise Timer::timeoutAfter(Duration delay, Promise&& promise) { + return promise.exclusiveJoin(afterDelay(delay).then([]() -> kj::Promise { + return makeTimeoutException(); + })); +} + +inline TimePoint TimerImpl::now() { return time; } + +} // namespace kj + +#endif // KJ_TIME_H_ diff --git a/phonelibs/capnp-cpp/include/kj/tuple.h b/phonelibs/capnp-cpp/include/kj/tuple.h new file mode 100644 index 00000000000000..2ea7276ec5af9a --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/tuple.h @@ -0,0 +1,364 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file defines a notion of tuples that is simpler that `std::tuple`. It works as follows: +// - `kj::Tuple is the type of a tuple of an A, a B, and a C. +// - `kj::tuple(a, b, c)` returns a tuple containing a, b, and c. If any of these are themselves +// tuples, they are flattened, so `tuple(a, tuple(b, c), d)` is equivalent to `tuple(a, b, c, d)`. +// - `kj::get(myTuple)` returns the element of `myTuple` at index n. +// - `kj::apply(func, ...)` calls func on the following arguments after first expanding any tuples +// in the argument list. So `kj::apply(foo, a, tuple(b, c), d)` would call `foo(a, b, c, d)`. +// +// Note that: +// - The type `Tuple` is a synonym for T. This is why `get` and `apply` are not members of the +// type. +// - It is illegal for an element of `Tuple` to itself be a tuple, as tuples are meant to be +// flattened. +// - It is illegal for an element of `Tuple` to be a reference, due to problems this would cause +// with type inference and `tuple()`. + +#ifndef KJ_TUPLE_H_ +#define KJ_TUPLE_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" + +namespace kj { +namespace _ { // private + +template +struct TypeByIndex_; +template +struct TypeByIndex_<0, First, Rest...> { + typedef First Type; +}; +template +struct TypeByIndex_ + : public TypeByIndex_ {}; +template +struct TypeByIndex_ { + static_assert(index != index, "Index out-of-range."); +}; +template +using TypeByIndex = typename TypeByIndex_::Type; +// Chose a particular type out of a list of types, by index. + +template +struct Indexes {}; +// Dummy helper type that just encapsulates a sequential list of indexes, so that we can match +// templates against them and unpack them with '...'. + +template +struct MakeIndexes_: public MakeIndexes_ {}; +template +struct MakeIndexes_<0, prefix...> { + typedef Indexes Type; +}; +template +using MakeIndexes = typename MakeIndexes_::Type; +// Equivalent to Indexes<0, 1, 2, ..., end>. + +template +class Tuple; +template +inline TypeByIndex& getImpl(Tuple& tuple); +template +inline TypeByIndex&& getImpl(Tuple&& tuple); +template +inline const TypeByIndex& getImpl(const Tuple& tuple); + +template +struct TupleElement { + // Encapsulates one element of a tuple. The actual tuple implementation multiply-inherits + // from a TupleElement for each element, which is more efficient than a recursive definition. + + T value; + TupleElement() = default; + constexpr inline TupleElement(const T& value): value(value) {} + constexpr inline TupleElement(T&& value): value(kj::mv(value)) {} +}; + +template +struct TupleElement { + // If tuples contained references, one of the following would have to be true: + // - `auto x = tuple(y, z)` would cause x to be a tuple of references to y and z, which is + // probably not what you expected. + // - `Tuple x = tuple(a, b)` would not work, because `tuple()` returned + // Tuple. + static_assert(sizeof(T*) == 0, "Sorry, tuples cannot contain references."); +}; + +template +struct TupleElement> { + static_assert(sizeof(Tuple*) == 0, + "Tuples cannot contain other tuples -- they should be flattened."); +}; + +template +struct TupleImpl; + +template +struct TupleImpl, Types...> + : public TupleElement... { + // Implementation of Tuple. The only reason we need this rather than rolling this into class + // Tuple (below) is so that we can get "indexes" as an unpackable list. + + static_assert(sizeof...(indexes) == sizeof...(Types), "Incorrect use of TupleImpl."); + + template + inline TupleImpl(Params&&... params) + : TupleElement(kj::fwd(params))... { + // Work around Clang 3.2 bug 16303 where this is not detected. (Unfortunately, Clang sometimes + // segfaults instead.) + static_assert(sizeof...(params) == sizeof...(indexes), + "Wrong number of parameters to Tuple constructor."); + } + + template + constexpr inline TupleImpl(Tuple&& other) + : TupleElement(kj::mv(getImpl(other)))... {} + template + constexpr inline TupleImpl(Tuple& other) + : TupleElement(getImpl(other))... {} + template + constexpr inline TupleImpl(const Tuple& other) + : TupleElement(getImpl(other))... {} +}; + +struct MakeTupleFunc; + +template +class Tuple { + // The actual Tuple class (used for tuples of size other than 1). + +public: + template + constexpr inline Tuple(Tuple&& other): impl(kj::mv(other)) {} + template + constexpr inline Tuple(Tuple& other): impl(other) {} + template + constexpr inline Tuple(const Tuple& other): impl(other) {} + +private: + template + constexpr Tuple(Params&&... params): impl(kj::fwd(params)...) {} + + TupleImpl, T...> impl; + + template + friend inline TypeByIndex& getImpl(Tuple& tuple); + template + friend inline TypeByIndex&& getImpl(Tuple&& tuple); + template + friend inline const TypeByIndex& getImpl(const Tuple& tuple); + friend struct MakeTupleFunc; +}; + +template <> +class Tuple<> { + // Simplified zero-member version of Tuple. In particular this is important to make sure that + // Tuple<>() is constexpr. +}; + +template +class Tuple; +// Single-element tuple should never be used. The public API should ensure this. + +template +inline TypeByIndex& getImpl(Tuple& tuple) { + // Get member of a Tuple by index, e.g. `get<2>(myTuple)`. + static_assert(index < sizeof...(T), "Tuple element index out-of-bounds."); + return implicitCast>&>(tuple.impl).value; +} +template +inline TypeByIndex&& getImpl(Tuple&& tuple) { + // Get member of a Tuple by index, e.g. `get<2>(myTuple)`. + static_assert(index < sizeof...(T), "Tuple element index out-of-bounds."); + return kj::mv(implicitCast>&>(tuple.impl).value); +} +template +inline const TypeByIndex& getImpl(const Tuple& tuple) { + // Get member of a Tuple by index, e.g. `get<2>(myTuple)`. + static_assert(index < sizeof...(T), "Tuple element index out-of-bounds."); + return implicitCast>&>(tuple.impl).value; +} +template +inline T&& getImpl(T&& value) { + // Get member of a Tuple by index, e.g. `getImpl<2>(myTuple)`. + + // Non-tuples are equivalent to one-element tuples. + static_assert(index == 0, "Tuple element index out-of-bounds."); + return kj::fwd(value); +} + + +template +struct ExpandAndApplyResult_; +// Template which computes the return type of applying Func to T... after flattening tuples. +// SoFar starts as Tuple<> and accumulates the flattened parameter types -- so after this template +// is recursively expanded, T... is empty and SoFar is a Tuple containing all the parameters. + +template +struct ExpandAndApplyResult_, First, Rest...> + : public ExpandAndApplyResult_, Rest...> {}; +template +struct ExpandAndApplyResult_, Tuple, Rest...> + : public ExpandAndApplyResult_, FirstTypes&&..., Rest...> {}; +template +struct ExpandAndApplyResult_, Tuple&, Rest...> + : public ExpandAndApplyResult_, FirstTypes&..., Rest...> {}; +template +struct ExpandAndApplyResult_, const Tuple&, Rest...> + : public ExpandAndApplyResult_, const FirstTypes&..., Rest...> {}; +template +struct ExpandAndApplyResult_> { + typedef decltype(instance()(instance()...)) Type; +}; +template +using ExpandAndApplyResult = typename ExpandAndApplyResult_, T...>::Type; +// Computes the expected return type of `expandAndApply()`. + +template +inline auto expandAndApply(Func&& func) -> ExpandAndApplyResult { + return func(); +} + +template +struct ExpandAndApplyFunc { + Func&& func; + First&& first; + ExpandAndApplyFunc(Func&& func, First&& first) + : func(kj::fwd(func)), first(kj::fwd(first)) {} + template + auto operator()(T&&... params) + -> decltype(this->func(kj::fwd(first), kj::fwd(params)...)) { + return this->func(kj::fwd(first), kj::fwd(params)...); + } +}; + +template +inline auto expandAndApply(Func&& func, First&& first, Rest&&... rest) + -> ExpandAndApplyResult { + + return expandAndApply( + ExpandAndApplyFunc(kj::fwd(func), kj::fwd(first)), + kj::fwd(rest)...); +} + +template +inline auto expandAndApply(Func&& func, Tuple&& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApplyWithIndexes(MakeIndexes(), + kj::fwd(func), kj::mv(first), kj::fwd(rest)...); +} + +template +inline auto expandAndApply(Func&& func, Tuple& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApplyWithIndexes(MakeIndexes(), + kj::fwd(func), first, kj::fwd(rest)...); +} + +template +inline auto expandAndApply(Func&& func, const Tuple& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApplyWithIndexes(MakeIndexes(), + kj::fwd(func), first, kj::fwd(rest)...); +} + +template +inline auto expandAndApplyWithIndexes( + Indexes, Func&& func, Tuple&& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApply(kj::fwd(func), kj::mv(getImpl(first))..., + kj::fwd(rest)...); +} + +template +inline auto expandAndApplyWithIndexes( + Indexes, Func&& func, const Tuple& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApply(kj::fwd(func), getImpl(first)..., + kj::fwd(rest)...); +} + +struct MakeTupleFunc { + template + Tuple...> operator()(Params&&... params) { + return Tuple...>(kj::fwd(params)...); + } + template + Decay operator()(Param&& param) { + return kj::fwd(param); + } +}; + +} // namespace _ (private) + +template struct Tuple_ { typedef _::Tuple Type; }; +template struct Tuple_ { typedef T Type; }; + +template using Tuple = typename Tuple_::Type; +// Tuple type. `Tuple` (i.e. a single-element tuple) is a synonym for `T`. Tuples of size +// other than 1 expand to an internal type. Either way, you can construct a Tuple using +// `kj::tuple(...)`, get an element by index `i` using `kj::get(myTuple)`, and expand the tuple +// as arguments to a function using `kj::apply(func, myTuple)`. +// +// Tuples are always flat -- that is, no element of a Tuple is ever itself a Tuple. If you +// construct a tuple from other tuples, the elements are flattened and concatenated. + +template +inline auto tuple(Params&&... params) + -> decltype(_::expandAndApply(_::MakeTupleFunc(), kj::fwd(params)...)) { + // Construct a new tuple from the given values. Any tuples in the argument list will be + // flattened into the result. + return _::expandAndApply(_::MakeTupleFunc(), kj::fwd(params)...); +} + +template +inline auto get(Tuple&& tuple) -> decltype(_::getImpl(kj::fwd(tuple))) { + // Unpack and return the tuple element at the given index. The index is specified as a template + // parameter, e.g. `kj::get<3>(myTuple)`. + return _::getImpl(kj::fwd(tuple)); +} + +template +inline auto apply(Func&& func, Params&&... params) + -> decltype(_::expandAndApply(kj::fwd(func), kj::fwd(params)...)) { + // Apply a function to some arguments, expanding tuples into separate arguments. + return _::expandAndApply(kj::fwd(func), kj::fwd(params)...); +} + +template struct TupleSize_ { static constexpr size_t size = 1; }; +template struct TupleSize_<_::Tuple> { + static constexpr size_t size = sizeof...(T); +}; + +template +constexpr size_t tupleSize() { return TupleSize_::size; } +// Returns size of the tuple T. + +} // namespace kj + +#endif // KJ_TUPLE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/units.h b/phonelibs/capnp-cpp/include/kj/units.h new file mode 100644 index 00000000000000..8bba40338bcc05 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/units.h @@ -0,0 +1,1172 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains types which are intended to help detect incorrect usage at compile +// time, but should then be optimized down to basic primitives (usually, integers) by the +// compiler. + +#ifndef KJ_UNITS_H_ +#define KJ_UNITS_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include + +namespace kj { + +// ======================================================================================= +// IDs + +template +struct Id { + // A type-safe numeric ID. `UnderlyingType` is the underlying integer representation. `Label` + // distinguishes this Id from other Id types. Sample usage: + // + // class Foo; + // typedef Id FooId; + // + // class Bar; + // typedef Id BarId; + // + // You can now use the FooId and BarId types without any possibility of accidentally using a + // FooId when you really wanted a BarId or vice-versa. + + UnderlyingType value; + + inline constexpr Id(): value(0) {} + inline constexpr explicit Id(int value): value(value) {} + + inline constexpr bool operator==(const Id& other) const { return value == other.value; } + inline constexpr bool operator!=(const Id& other) const { return value != other.value; } + inline constexpr bool operator<=(const Id& other) const { return value <= other.value; } + inline constexpr bool operator>=(const Id& other) const { return value >= other.value; } + inline constexpr bool operator< (const Id& other) const { return value < other.value; } + inline constexpr bool operator> (const Id& other) const { return value > other.value; } +}; + +// ======================================================================================= +// Quantity and UnitRatio -- implement unit analysis via the type system + +struct Unsafe_ {}; +constexpr Unsafe_ unsafe = Unsafe_(); +// Use as a parameter to constructors that are unsafe to indicate that you really do mean it. + +template +class Bounded; +template +class BoundedConst; + +template constexpr bool isIntegral() { return false; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } + +template +struct IsIntegralOrBounded_ { static constexpr bool value = isIntegral(); }; +template +struct IsIntegralOrBounded_> { static constexpr bool value = true; }; +template +struct IsIntegralOrBounded_> { static constexpr bool value = true; }; + +template +inline constexpr bool isIntegralOrBounded() { return IsIntegralOrBounded_::value; } + +template +class UnitRatio { + // A multiplier used to convert Quantities of one unit to Quantities of another unit. See + // Quantity, below. + // + // Construct this type by dividing one Quantity by another of a different unit. Use this type + // by multiplying it by a Quantity, or dividing a Quantity by it. + + static_assert(isIntegralOrBounded(), + "Underlying type for UnitRatio must be integer."); + +public: + inline UnitRatio() {} + + constexpr UnitRatio(Number unit1PerUnit2, decltype(unsafe)): unit1PerUnit2(unit1PerUnit2) {} + // This constructor was intended to be private, but GCC complains about it being private in a + // bunch of places that don't appear to even call it, so I made it public. Oh well. + + template + inline constexpr UnitRatio(const UnitRatio& other) + : unit1PerUnit2(other.unit1PerUnit2) {} + + template + inline constexpr UnitRatio + operator+(UnitRatio other) const { + return UnitRatio( + unit1PerUnit2 + other.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator-(UnitRatio other) const { + return UnitRatio( + unit1PerUnit2 - other.unit1PerUnit2, unsafe); + } + + template + inline constexpr UnitRatio + operator*(UnitRatio other) const { + // U1 / U2 * U3 / U1 = U3 / U2 + return UnitRatio( + unit1PerUnit2 * other.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator*(UnitRatio other) const { + // U1 / U2 * U2 / U3 = U1 / U3 + return UnitRatio( + unit1PerUnit2 * other.unit1PerUnit2, unsafe); + } + + template + inline constexpr UnitRatio + operator/(UnitRatio other) const { + // (U1 / U2) / (U1 / U3) = U3 / U2 + return UnitRatio( + unit1PerUnit2 / other.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator/(UnitRatio other) const { + // (U1 / U2) / (U3 / U2) = U1 / U3 + return UnitRatio( + unit1PerUnit2 / other.unit1PerUnit2, unsafe); + } + + template + inline decltype(Number() / OtherNumber()) + operator/(UnitRatio other) const { + return unit1PerUnit2 / other.unit1PerUnit2; + } + + inline bool operator==(UnitRatio other) const { return unit1PerUnit2 == other.unit1PerUnit2; } + inline bool operator!=(UnitRatio other) const { return unit1PerUnit2 != other.unit1PerUnit2; } + +private: + Number unit1PerUnit2; + + template + friend class Quantity; + template + friend class UnitRatio; + + template + friend inline constexpr UnitRatio + operator*(N1, UnitRatio); +}; + +template () && isIntegralOrBounded()>> +inline constexpr UnitRatio + operator*(N1 n, UnitRatio r) { + return UnitRatio(n * r.unit1PerUnit2, unsafe); +} + +template +class Quantity { + // A type-safe numeric quantity, specified in terms of some unit. Two Quantities cannot be used + // in arithmetic unless they use the same unit. The `Unit` type parameter is only used to prevent + // accidental mixing of units; this type is never instantiated and can very well be incomplete. + // `Number` is the underlying primitive numeric type. + // + // Quantities support most basic arithmetic operators, intelligently handling units, and + // automatically casting the underlying type in the same way that the compiler would. + // + // To convert a primitive number to a Quantity, multiply it by unit>(). + // To convert a Quantity to a primitive number, divide it by unit>(). + // To convert a Quantity of one unit to another unit, multiply or divide by a UnitRatio. + // + // The Quantity class is not well-suited to hardcore physics as it does not allow multiplying + // one quantity by another. For example, multiplying meters by meters won't get you square + // meters; it will get you a compiler error. It would be interesting to see if template + // metaprogramming could properly deal with such things but this isn't needed for the present + // use case. + // + // Sample usage: + // + // class SecondsLabel; + // typedef Quantity Seconds; + // constexpr Seconds SECONDS = unit(); + // + // class MinutesLabel; + // typedef Quantity Minutes; + // constexpr Minutes MINUTES = unit(); + // + // constexpr UnitRatio SECONDS_PER_MINUTE = + // 60 * SECONDS / MINUTES; + // + // void waitFor(Seconds seconds) { + // sleep(seconds / SECONDS); + // } + // void waitFor(Minutes minutes) { + // waitFor(minutes * SECONDS_PER_MINUTE); + // } + // + // void waitThreeMinutes() { + // waitFor(3 * MINUTES); + // } + + static_assert(isIntegralOrBounded(), + "Underlying type for Quantity must be integer."); + +public: + inline constexpr Quantity() = default; + + inline constexpr Quantity(MaxValue_): value(maxValue) {} + inline constexpr Quantity(MinValue_): value(minValue) {} + // Allow initialization from maxValue and minValue. + // TODO(msvc): decltype(maxValue) and decltype(minValue) deduce unknown-type for these function + // parameters, causing the compiler to complain of a duplicate constructor definition, so we + // specify MaxValue_ and MinValue_ types explicitly. + + inline constexpr Quantity(Number value, decltype(unsafe)): value(value) {} + // This constructor was intended to be private, but GCC complains about it being private in a + // bunch of places that don't appear to even call it, so I made it public. Oh well. + + template + inline constexpr Quantity(const Quantity& other) + : value(other.value) {} + + template + inline Quantity& operator=(const Quantity& other) { + value = other.value; + return *this; + } + + template + inline constexpr Quantity + operator+(const Quantity& other) const { + return Quantity(value + other.value, unsafe); + } + template + inline constexpr Quantity + operator-(const Quantity& other) const { + return Quantity(value - other.value, unsafe); + } + template ()>> + inline constexpr Quantity + operator*(OtherNumber other) const { + return Quantity(value * other, unsafe); + } + template ()>> + inline constexpr Quantity + operator/(OtherNumber other) const { + return Quantity(value / other, unsafe); + } + template + inline constexpr decltype(Number() / OtherNumber()) + operator/(const Quantity& other) const { + return value / other.value; + } + template + inline constexpr Quantity + operator%(const Quantity& other) const { + return Quantity(value % other.value, unsafe); + } + + template + inline constexpr Quantity + operator*(UnitRatio ratio) const { + return Quantity( + value * ratio.unit1PerUnit2, unsafe); + } + template + inline constexpr Quantity + operator/(UnitRatio ratio) const { + return Quantity( + value / ratio.unit1PerUnit2, unsafe); + } + template + inline constexpr Quantity + operator%(UnitRatio ratio) const { + return Quantity( + value % ratio.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator/(Quantity other) const { + return UnitRatio( + value / other.value, unsafe); + } + + template + inline constexpr bool operator==(const Quantity& other) const { + return value == other.value; + } + template + inline constexpr bool operator!=(const Quantity& other) const { + return value != other.value; + } + template + inline constexpr bool operator<=(const Quantity& other) const { + return value <= other.value; + } + template + inline constexpr bool operator>=(const Quantity& other) const { + return value >= other.value; + } + template + inline constexpr bool operator<(const Quantity& other) const { + return value < other.value; + } + template + inline constexpr bool operator>(const Quantity& other) const { + return value > other.value; + } + + template + inline Quantity& operator+=(const Quantity& other) { + value += other.value; + return *this; + } + template + inline Quantity& operator-=(const Quantity& other) { + value -= other.value; + return *this; + } + template + inline Quantity& operator*=(OtherNumber other) { + value *= other; + return *this; + } + template + inline Quantity& operator/=(OtherNumber other) { + value /= other.value; + return *this; + } + +private: + Number value; + + template + friend class Quantity; + + template + friend inline constexpr auto operator*(Number1 a, Quantity b) + -> Quantity; +}; + +template struct Unit_ { + static inline constexpr T get() { return T(1); } +}; +template +struct Unit_> { + static inline constexpr Quantity::get()), U> get() { + return Quantity::get()), U>(Unit_::get(), unsafe); + } +}; + +template +inline constexpr auto unit() -> decltype(Unit_::get()) { return Unit_::get(); } +// unit>() returns a Quantity of value 1. It also, intentionally, works on basic +// numeric types. + +template +inline constexpr auto operator*(Number1 a, Quantity b) + -> Quantity { + return Quantity(a * b.value, unsafe); +} + +template +inline constexpr auto operator*(UnitRatio ratio, + Quantity measure) + -> decltype(measure * ratio) { + return measure * ratio; +} + +// ======================================================================================= +// Absolute measures + +template +class Absolute { + // Wraps some other value -- typically a Quantity -- but represents a value measured based on + // some absolute origin. For example, if `Duration` is a type representing a time duration, + // Absolute might be a calendar date. + // + // Since Absolute represents measurements relative to some arbitrary origin, the only sensible + // arithmetic to perform on them is addition and subtraction. + + // TODO(someday): Do the same automatic expansion of integer width that Quantity does? Doesn't + // matter for our time use case, where we always use 64-bit anyway. Note that fixing this + // would implicitly allow things like multiplying an Absolute by a UnitRatio to change its + // units, which is actually totally logical and kind of neat. + +public: + inline constexpr Absolute operator+(const T& other) const { return Absolute(value + other); } + inline constexpr Absolute operator-(const T& other) const { return Absolute(value - other); } + inline constexpr T operator-(const Absolute& other) const { return value - other.value; } + + inline Absolute& operator+=(const T& other) { value += other; return *this; } + inline Absolute& operator-=(const T& other) { value -= other; return *this; } + + inline constexpr bool operator==(const Absolute& other) const { return value == other.value; } + inline constexpr bool operator!=(const Absolute& other) const { return value != other.value; } + inline constexpr bool operator<=(const Absolute& other) const { return value <= other.value; } + inline constexpr bool operator>=(const Absolute& other) const { return value >= other.value; } + inline constexpr bool operator< (const Absolute& other) const { return value < other.value; } + inline constexpr bool operator> (const Absolute& other) const { return value > other.value; } + +private: + T value; + + explicit constexpr Absolute(T value): value(value) {} + + template + friend inline constexpr U origin(); +}; + +template +inline constexpr Absolute operator+(const T& a, const Absolute& b) { + return b + a; +} + +template struct UnitOf_ { typedef T Type; }; +template struct UnitOf_> { typedef T Type; }; +template +using UnitOf = typename UnitOf_::Type; +// UnitOf> is T. UnitOf is AnythingElse. + +template +inline constexpr T origin() { return T(0 * unit>()); } +// origin>() returns an Absolute of value 0. It also, intentionally, works on basic +// numeric types. + +// ======================================================================================= +// Overflow avoidance + +template +struct BitCount_ { + static constexpr uint value = BitCount_<(n >> 1), accum + 1>::value; +}; +template +struct BitCount_<0, accum> { + static constexpr uint value = accum; +}; + +template +inline constexpr uint bitCount() { return BitCount_::value; } +// Number of bits required to represent the number `n`. + +template struct AtLeastUInt_ { + static_assert(bitCountBitCount < 7, "don't know how to represent integers over 64 bits"); +}; +template <> struct AtLeastUInt_<0> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<1> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<2> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<3> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<4> { typedef uint16_t Type; }; +template <> struct AtLeastUInt_<5> { typedef uint32_t Type; }; +template <> struct AtLeastUInt_<6> { typedef uint64_t Type; }; + +template +using AtLeastUInt = typename AtLeastUInt_()>::Type; +// AtLeastUInt is an unsigned integer of at least n bits. E.g. AtLeastUInt<12> is uint16_t. + +// ------------------------------------------------------------------- + +template +class BoundedConst { + // A constant integer value on which we can do bit size analysis. + +public: + BoundedConst() = default; + + inline constexpr uint unwrap() const { return value; } + +#define OP(op, check) \ + template \ + inline constexpr BoundedConst<(value op other)> \ + operator op(BoundedConst) const { \ + static_assert(check, "overflow in BoundedConst arithmetic"); \ + return BoundedConst<(value op other)>(); \ + } +#define COMPARE_OP(op) \ + template \ + inline constexpr bool operator op(BoundedConst) const { \ + return value op other; \ + } + + OP(+, value + other >= value) + OP(-, value - other <= value) + OP(*, value * other / other == value) + OP(/, true) // div by zero already errors out; no other division ever overflows + OP(%, true) // mod by zero already errors out; no other modulus ever overflows + OP(<<, value << other >= value) + OP(>>, true) // right shift can't overflow + OP(&, true) // bitwise ops can't overflow + OP(|, true) // bitwise ops can't overflow + + COMPARE_OP(==) + COMPARE_OP(!=) + COMPARE_OP(< ) + COMPARE_OP(> ) + COMPARE_OP(<=) + COMPARE_OP(>=) +#undef OP +#undef COMPARE_OP +}; + +template +struct Unit_> { + static inline constexpr BoundedConst<1> get() { return BoundedConst<1>(); } +}; + +template +struct Unit_> { + static inline constexpr BoundedConst<1> get() { return BoundedConst<1>(); } +}; + +template +inline constexpr BoundedConst bounded() { + return BoundedConst(); +} + +template +static constexpr uint64_t boundedAdd() { + static_assert(a + b >= a, "possible overflow detected"); + return a + b; +} +template +static constexpr uint64_t boundedSub() { + static_assert(a - b <= a, "possible underflow detected"); + return a - b; +} +template +static constexpr uint64_t boundedMul() { + static_assert(a * b / b == a, "possible overflow detected"); + return a * b; +} +template +static constexpr uint64_t boundedLShift() { + static_assert(a << b >= a, "possible overflow detected"); + return a << b; +} + +template +inline constexpr BoundedConst min(BoundedConst, BoundedConst) { + return bounded(); +} +template +inline constexpr BoundedConst max(BoundedConst, BoundedConst) { + return bounded(); +} +// We need to override min() and max() between constants because the ternary operator in the +// default implementation would complain. + +// ------------------------------------------------------------------- + +template +class Bounded { +public: + static_assert(maxN <= T(kj::maxValue), "possible overflow detected"); + + Bounded() = default; + + Bounded(const Bounded& other) = default; + template ()>> + inline constexpr Bounded(OtherInt value): value(value) { + static_assert(OtherInt(maxValue) <= maxN, "possible overflow detected"); + } + template + inline constexpr Bounded(const Bounded& other) + : value(other.value) { + static_assert(otherMax <= maxN, "possible overflow detected"); + } + template + inline constexpr Bounded(BoundedConst) + : value(otherValue) { + static_assert(otherValue <= maxN, "overflow detected"); + } + + Bounded& operator=(const Bounded& other) = default; + template ()>> + Bounded& operator=(OtherInt other) { + static_assert(OtherInt(maxValue) <= maxN, "possible overflow detected"); + value = other; + return *this; + } + template + inline Bounded& operator=(const Bounded& other) { + static_assert(otherMax <= maxN, "possible overflow detected"); + value = other.value; + return *this; + } + template + inline Bounded& operator=(BoundedConst) { + static_assert(otherValue <= maxN, "overflow detected"); + value = otherValue; + return *this; + } + + inline constexpr T unwrap() const { return value; } + +#define OP(op, newMax) \ + template \ + inline constexpr Bounded \ + operator op(const Bounded& other) const { \ + return Bounded(value op other.value, unsafe); \ + } +#define COMPARE_OP(op) \ + template \ + inline constexpr bool operator op(const Bounded& other) const { \ + return value op other.value; \ + } + + OP(+, (boundedAdd())) + OP(*, (boundedMul())) + OP(/, maxN) + OP(%, otherMax - 1) + + // operator- is intentionally omitted because we mostly use this with unsigned types, and + // subtraction requires proof that subtrahend is not greater than the minuend. + + COMPARE_OP(==) + COMPARE_OP(!=) + COMPARE_OP(< ) + COMPARE_OP(> ) + COMPARE_OP(<=) + COMPARE_OP(>=) + +#undef OP +#undef COMPARE_OP + + template + inline Bounded assertMax(ErrorFunc&& func) const { + // Assert that the number is no more than `newMax`. Otherwise, call `func`. + static_assert(newMax < maxN, "this bounded size assertion is redundant"); + if (KJ_UNLIKELY(value > newMax)) func(); + return Bounded(value, unsafe); + } + + template + inline Bounded subtractChecked( + const Bounded& other, ErrorFunc&& func) const { + // Subtract a number, calling func() if the result would underflow. + if (KJ_UNLIKELY(value < other.value)) func(); + return Bounded(value - other.value, unsafe); + } + + template + inline Bounded subtractChecked( + BoundedConst, ErrorFunc&& func) const { + // Subtract a number, calling func() if the result would underflow. + static_assert(otherValue <= maxN, "underflow detected"); + if (KJ_UNLIKELY(value < otherValue)) func(); + return Bounded(value - otherValue, unsafe); + } + + template + inline Maybe> trySubtract( + const Bounded& other) const { + // Subtract a number, calling func() if the result would underflow. + if (value < other.value) { + return nullptr; + } else { + return Bounded(value - other.value, unsafe); + } + } + + template + inline Maybe> trySubtract(BoundedConst) const { + // Subtract a number, calling func() if the result would underflow. + if (value < otherValue) { + return nullptr; + } else { + return Bounded(value - otherValue, unsafe); + } + } + + inline constexpr Bounded(T value, decltype(unsafe)): value(value) {} + template + inline constexpr Bounded(Bounded value, decltype(unsafe)) + : value(value.value) {} + // Mainly for internal use. + // + // Only use these as a last resort, with ample commentary on why you think it's safe. + +private: + T value; + + template + friend class Bounded; +}; + +template +inline constexpr Bounded bounded(Number value) { + return Bounded(value, unsafe); +} + +inline constexpr Bounded<1, uint8_t> bounded(bool value) { + return Bounded<1, uint8_t>(value, unsafe); +} + +template +inline constexpr Bounded(), Number> assumeBits(Number value) { + return Bounded(), Number>(value, unsafe); +} + +template +inline constexpr Bounded(), T> assumeBits(Bounded value) { + return Bounded(), T>(value, unsafe); +} + +template +inline constexpr auto assumeBits(Quantity value) + -> Quantity(value / unit>())), Unit> { + return Quantity(value / unit>())), Unit>( + assumeBits(value / unit>()), unsafe); +} + +template +inline constexpr Bounded assumeMax(Number value) { + return Bounded(value, unsafe); +} + +template +inline constexpr Bounded assumeMax(Bounded value) { + return Bounded(value, unsafe); +} + +template +inline constexpr auto assumeMax(Quantity value) + -> Quantity(value / unit>())), Unit> { + return Quantity(value / unit>())), Unit>( + assumeMax(value / unit>()), unsafe); +} + +template +inline constexpr Bounded assumeMax(BoundedConst, Number value) { + return assumeMax(value); +} + +template +inline constexpr Bounded assumeMax(BoundedConst, Bounded value) { + return assumeMax(value); +} + +template +inline constexpr auto assumeMax(Quantity, Unit>, Quantity value) + -> decltype(assumeMax(value)) { + return assumeMax(value); +} + +template +inline Bounded assertMax(Bounded value, ErrorFunc&& errorFunc) { + // Assert that the bounded value is less than or equal to the given maximum, calling errorFunc() + // if not. + static_assert(newMax < maxN, "this bounded size assertion is redundant"); + return value.template assertMax(kj::fwd(errorFunc)); +} + +template +inline Quantity, Unit> assertMax( + Quantity, Unit> value, ErrorFunc&& errorFunc) { + // Assert that the bounded value is less than or equal to the given maximum, calling errorFunc() + // if not. + static_assert(newMax < maxN, "this bounded size assertion is redundant"); + return (value / unit()).template assertMax( + kj::fwd(errorFunc)) * unit(); +} + +template +inline Bounded assertMax( + BoundedConst, Bounded value, ErrorFunc&& errorFunc) { + return assertMax(value, kj::mv(errorFunc)); +} + +template +inline Quantity, Unit> assertMax( + Quantity, Unit>, + Quantity, Unit> value, ErrorFunc&& errorFunc) { + return assertMax(value, kj::mv(errorFunc)); +} + +template +inline Bounded(), T> assertMaxBits( + Bounded value, ErrorFunc&& errorFunc = ErrorFunc()) { + // Assert that the bounded value requires no more than the given number of bits, calling + // errorFunc() if not. + return assertMax()>(value, kj::fwd(errorFunc)); +} + +template +inline Quantity(), T>, Unit> assertMaxBits( + Quantity, Unit> value, ErrorFunc&& errorFunc = ErrorFunc()) { + // Assert that the bounded value requires no more than the given number of bits, calling + // errorFunc() if not. + return assertMax()>(value, kj::fwd(errorFunc)); +} + +template +inline constexpr Bounded upgradeBound(Bounded value) { + return value; +} + +template +inline constexpr Quantity, Unit> upgradeBound( + Quantity, Unit> value) { + return value; +} + +template +inline auto subtractChecked(Bounded value, Other other, ErrorFunc&& errorFunc) + -> decltype(value.subtractChecked(other, kj::fwd(errorFunc))) { + return value.subtractChecked(other, kj::fwd(errorFunc)); +} + +template +inline auto subtractChecked(Quantity value, Quantity other, ErrorFunc&& errorFunc) + -> Quantity(errorFunc))), Unit> { + return subtractChecked(value / unit>(), + other / unit>(), + kj::fwd(errorFunc)) + * unit>(); +} + +template +inline auto trySubtract(Bounded value, Other other) + -> decltype(value.trySubtract(other)) { + return value.trySubtract(other); +} + +template +inline auto trySubtract(Quantity value, Quantity other) + -> Maybe> { + return trySubtract(value / unit>(), + other / unit>()) + .map([](decltype(subtractChecked(T(), U(), int())) x) { + return x * unit>(); + }); +} + +template +inline constexpr Bounded> +min(Bounded a, Bounded b) { + return Bounded>(kj::min(a.unwrap(), b.unwrap()), unsafe); +} +template +inline constexpr Bounded> +max(Bounded a, Bounded b) { + return Bounded>(kj::max(a.unwrap(), b.unwrap()), unsafe); +} +// We need to override min() and max() because: +// 1) WiderType<> might not choose the correct bounds. +// 2) One of the two sides of the ternary operator in the default implementation would fail to +// typecheck even though it is OK in practice. + +// ------------------------------------------------------------------- +// Operators between Bounded and BoundedConst + +#define OP(op, newMax) \ +template \ +inline constexpr Bounded<(newMax), decltype(T() op uint())> operator op( \ + Bounded value, BoundedConst) { \ + return Bounded<(newMax), decltype(T() op uint())>(value.unwrap() op cvalue, unsafe); \ +} + +#define REVERSE_OP(op, newMax) \ +template \ +inline constexpr Bounded<(newMax), decltype(uint() op T())> operator op( \ + BoundedConst, Bounded value) { \ + return Bounded<(newMax), decltype(uint() op T())>(cvalue op value.unwrap(), unsafe); \ +} + +#define COMPARE_OP(op) \ +template \ +inline constexpr bool operator op(Bounded value, BoundedConst) { \ + return value.unwrap() op cvalue; \ +} \ +template \ +inline constexpr bool operator op(BoundedConst, Bounded value) { \ + return cvalue op value.unwrap(); \ +} + +OP(+, (boundedAdd())) +REVERSE_OP(+, (boundedAdd())) + +OP(*, (boundedMul())) +REVERSE_OP(*, (boundedAdd())) + +OP(/, maxN / cvalue) +REVERSE_OP(/, cvalue) // denominator could be 1 + +OP(%, cvalue - 1) +REVERSE_OP(%, maxN - 1) + +OP(<<, (boundedLShift())) +REVERSE_OP(<<, (boundedLShift())) + +OP(>>, maxN >> cvalue) +REVERSE_OP(>>, cvalue >> maxN) + +OP(&, maxValueForBits()>() & cvalue) +REVERSE_OP(&, maxValueForBits()>() & cvalue) + +OP(|, maxN | cvalue) +REVERSE_OP(|, maxN | cvalue) + +COMPARE_OP(==) +COMPARE_OP(!=) +COMPARE_OP(< ) +COMPARE_OP(> ) +COMPARE_OP(<=) +COMPARE_OP(>=) + +#undef OP +#undef REVERSE_OP +#undef COMPARE_OP + +template +inline constexpr Bounded + operator-(BoundedConst, Bounded value) { + // We allow subtraction of a variable from a constant only if the constant is greater than or + // equal to the maximum possible value of the variable. Since the variable could be zero, the + // result can be as large as the constant. + // + // We do not allow subtraction of a constant from a variable because there's never a guarantee it + // won't underflow (unless the constant is zero, which is silly). + static_assert(cvalue >= maxN, "possible underflow detected"); + return Bounded(cvalue - value.unwrap(), unsafe); +} + +template +inline constexpr Bounded min(Bounded a, BoundedConst) { + return Bounded(kj::min(b, a.unwrap()), unsafe); +} +template +inline constexpr Bounded min(BoundedConst, Bounded a) { + return Bounded(kj::min(a.unwrap(), b), unsafe); +} +template +inline constexpr Bounded max(Bounded a, BoundedConst) { + return Bounded(kj::max(b, a.unwrap()), unsafe); +} +template +inline constexpr Bounded max(BoundedConst, Bounded a) { + return Bounded(kj::max(a.unwrap(), b), unsafe); +} +// We need to override min() between a Bounded and a constant since: +// 1) WiderType<> might choose BoundedConst over a 1-byte Bounded, which is wrong. +// 2) To clamp the bounds of the output type. +// 3) Same ternary operator typechecking issues. + +// ------------------------------------------------------------------- + +template +class SafeUnwrapper { +public: + inline explicit constexpr SafeUnwrapper(Bounded value): value(value.unwrap()) {} + + template ()>> + inline constexpr operator U() const { + static_assert(maxN <= U(maxValue), "possible truncation detected"); + return value; + } + + inline constexpr operator bool() const { + static_assert(maxN <= 1, "possible truncation detected"); + return value; + } + +private: + T value; +}; + +template +inline constexpr SafeUnwrapper unbound(Bounded bounded) { + // Unwraps the bounded value, returning a value that can be implicitly cast to any integer type. + // If this implicit cast could truncate, a compile-time error will be raised. + return SafeUnwrapper(bounded); +} + +template +class SafeConstUnwrapper { +public: + template ()>> + inline constexpr operator T() const { + static_assert(value <= T(maxValue), "this operation will truncate"); + return value; + } + + inline constexpr operator bool() const { + static_assert(value <= 1, "this operation will truncate"); + return value; + } +}; + +template +inline constexpr SafeConstUnwrapper unbound(BoundedConst) { + return SafeConstUnwrapper(); +} + +template +inline constexpr T unboundAs(U value) { + return unbound(value); +} + +template +inline constexpr T unboundMax(Bounded value) { + // Explicitly ungaurd expecting a value that is at most `maxN`. + static_assert(maxN <= requestedMax, "possible overflow detected"); + return value.unwrap(); +} + +template +inline constexpr uint unboundMax(BoundedConst) { + // Explicitly ungaurd expecting a value that is at most `maxN`. + static_assert(value <= requestedMax, "overflow detected"); + return value; +} + +template +inline constexpr auto unboundMaxBits(T value) -> + decltype(unboundMax()>(value)) { + // Explicitly ungaurd expecting a value that fits into `bits` bits. + return unboundMax()>(value); +} + +#define OP(op) \ +template \ +inline constexpr auto operator op(T a, SafeUnwrapper b) -> decltype(a op (T)b) { \ + return a op (AtLeastUInt)b; \ +} \ +template \ +inline constexpr auto operator op(SafeUnwrapper b, T a) -> decltype((T)b op a) { \ + return (AtLeastUInt)b op a; \ +} \ +template \ +inline constexpr auto operator op(T a, SafeConstUnwrapper b) -> decltype(a op (T)b) { \ + return a op (AtLeastUInt)b; \ +} \ +template \ +inline constexpr auto operator op(SafeConstUnwrapper b, T a) -> decltype((T)b op a) { \ + return (AtLeastUInt)b op a; \ +} + +OP(+) +OP(-) +OP(*) +OP(/) +OP(%) +OP(<<) +OP(>>) +OP(&) +OP(|) +OP(==) +OP(!=) +OP(<=) +OP(>=) +OP(<) +OP(>) + +#undef OP + +// ------------------------------------------------------------------- + +template +class Range> { +public: + inline constexpr Range(Bounded begin, Bounded end) + : inner(unbound(begin), unbound(end)) {} + inline explicit constexpr Range(Bounded end) + : inner(unbound(end)) {} + + class Iterator { + public: + Iterator() = default; + inline explicit Iterator(typename Range::Iterator inner): inner(inner) {} + + inline Bounded operator* () const { return Bounded(*inner, unsafe); } + inline Iterator& operator++() { ++inner; return *this; } + + inline bool operator==(const Iterator& other) const { return inner == other.inner; } + inline bool operator!=(const Iterator& other) const { return inner != other.inner; } + + private: + typename Range::Iterator inner; + }; + + inline Iterator begin() const { return Iterator(inner.begin()); } + inline Iterator end() const { return Iterator(inner.end()); } + +private: + Range inner; +}; + +template +class Range> { +public: + inline constexpr Range(Quantity begin, Quantity end) + : inner(begin / unit>(), end / unit>()) {} + inline explicit constexpr Range(Quantity end) + : inner(end / unit>()) {} + + class Iterator { + public: + Iterator() = default; + inline explicit Iterator(typename Range::Iterator inner): inner(inner) {} + + inline Quantity operator* () const { return *inner * unit>(); } + inline Iterator& operator++() { ++inner; return *this; } + + inline bool operator==(const Iterator& other) const { return inner == other.inner; } + inline bool operator!=(const Iterator& other) const { return inner != other.inner; } + + private: + typename Range::Iterator inner; + }; + + inline Iterator begin() const { return Iterator(inner.begin()); } + inline Iterator end() const { return Iterator(inner.end()); } + +private: + Range inner; +}; + +template +inline constexpr Range> zeroTo(BoundedConst end) { + return Range>(end); +} + +template +inline constexpr Range, Unit>> + zeroTo(Quantity, Unit> end) { + return Range, Unit>>(end); +} + +} // namespace kj + +#endif // KJ_UNITS_H_ diff --git a/phonelibs/capnp-cpp/include/kj/vector.h b/phonelibs/capnp-cpp/include/kj/vector.h new file mode 100644 index 00000000000000..44613f333173cd --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/vector.h @@ -0,0 +1,144 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_VECTOR_H_ +#define KJ_VECTOR_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "array.h" + +namespace kj { + +template +class Vector { + // Similar to std::vector, but based on KJ framework. + // + // This implementation always uses move constructors when growing the backing array. If the + // move constructor throws, the Vector is left in an inconsistent state. This is acceptable + // under KJ exception theory which assumes that exceptions leave things in inconsistent states. + + // TODO(someday): Allow specifying a custom allocator. + +public: + inline Vector() = default; + inline explicit Vector(size_t capacity): builder(heapArrayBuilder(capacity)) {} + + inline operator ArrayPtr() { return builder; } + inline operator ArrayPtr() const { return builder; } + inline ArrayPtr asPtr() { return builder.asPtr(); } + inline ArrayPtr asPtr() const { return builder.asPtr(); } + + inline size_t size() const { return builder.size(); } + inline bool empty() const { return size() == 0; } + inline size_t capacity() const { return builder.capacity(); } + inline T& operator[](size_t index) const { return builder[index]; } + + inline const T* begin() const { return builder.begin(); } + inline const T* end() const { return builder.end(); } + inline const T& front() const { return builder.front(); } + inline const T& back() const { return builder.back(); } + inline T* begin() { return builder.begin(); } + inline T* end() { return builder.end(); } + inline T& front() { return builder.front(); } + inline T& back() { return builder.back(); } + + inline Array releaseAsArray() { + // TODO(perf): Avoid a copy/move by allowing Array to point to incomplete space? + if (!builder.isFull()) { + setCapacity(size()); + } + return builder.finish(); + } + + template + inline T& add(Params&&... params) { + if (builder.isFull()) grow(); + return builder.add(kj::fwd(params)...); + } + + template + inline void addAll(Iterator begin, Iterator end) { + size_t needed = builder.size() + (end - begin); + if (needed > builder.capacity()) grow(needed); + builder.addAll(begin, end); + } + + template + inline void addAll(Container&& container) { + addAll(container.begin(), container.end()); + } + + inline void removeLast() { + builder.removeLast(); + } + + inline void resize(size_t size) { + if (size > builder.capacity()) grow(size); + builder.resize(size); + } + + inline void operator=(decltype(nullptr)) { + builder = nullptr; + } + + inline void clear() { + while (builder.size() > 0) { + builder.removeLast(); + } + } + + inline void truncate(size_t size) { + builder.truncate(size); + } + + inline void reserve(size_t size) { + if (size > builder.capacity()) { + setCapacity(size); + } + } + +private: + ArrayBuilder builder; + + void grow(size_t minCapacity = 0) { + setCapacity(kj::max(minCapacity, capacity() == 0 ? 4 : capacity() * 2)); + } + void setCapacity(size_t newSize) { + if (builder.size() > newSize) { + builder.truncate(newSize); + } + ArrayBuilder newBuilder = heapArrayBuilder(newSize); + newBuilder.addAll(kj::mv(builder)); + builder = kj::mv(newBuilder); + } +}; + +template +inline auto KJ_STRINGIFY(const Vector& v) -> decltype(toCharSequence(v.asPtr())) { + return toCharSequence(v.asPtr()); +} + +} // namespace kj + +#endif // KJ_VECTOR_H_ diff --git a/phonelibs/capnp-cpp/include/kj/windows-sanity.h b/phonelibs/capnp-cpp/include/kj/windows-sanity.h new file mode 100644 index 00000000000000..766ba2cbd67047 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/windows-sanity.h @@ -0,0 +1,41 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_WINDOWS_SANITY_H_ +#define KJ_WINDOWS_SANITY_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#ifndef _INC_WINDOWS +#error "windows.h needs to be included before kj/windows-sanity.h (or perhaps you don't need either?)" +#endif + +namespace win32 { + const auto ERROR_ = ERROR; +#undef ERROR + const auto ERROR = ERROR_; +} + +using win32::ERROR; + +#endif // KJ_WINDOWS_SANITY_H_ diff --git a/phonelibs/libgralloc/include/gralloc_priv.h b/phonelibs/libgralloc/include/gralloc_priv.h new file mode 100644 index 00000000000000..4aa47541b03c04 --- /dev/null +++ b/phonelibs/libgralloc/include/gralloc_priv.h @@ -0,0 +1,296 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * Copyright (c) 2011-2015, The Linux Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef GRALLOC_PRIV_H_ +#define GRALLOC_PRIV_H_ + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#define ROUND_UP_PAGESIZE(x) ( (((unsigned long)(x)) + PAGE_SIZE-1) & \ + (~(PAGE_SIZE-1)) ) + +/* Gralloc usage bits indicating the type of allocation that should be used */ +/* SYSTEM heap comes from kernel vmalloc (ION_SYSTEM_HEAP_ID) + * is cached by default and + * is not secured */ + +/* GRALLOC_USAGE_PRIVATE_0 is unused */ + +/* Non linear, Universal Bandwidth Compression */ +#define GRALLOC_USAGE_PRIVATE_ALLOC_UBWC GRALLOC_USAGE_PRIVATE_1 + +/* IOMMU heap comes from manually allocated pages, can be cached/uncached, + * is not secured */ +#define GRALLOC_USAGE_PRIVATE_IOMMU_HEAP GRALLOC_USAGE_PRIVATE_2 + +/* MM heap is a carveout heap for video, can be secured */ +#define GRALLOC_USAGE_PRIVATE_MM_HEAP GRALLOC_USAGE_PRIVATE_3 + +/* ADSP heap is a carveout heap, is not secured */ +#define GRALLOC_USAGE_PRIVATE_ADSP_HEAP 0x01000000 + +/* Set this for allocating uncached memory (using O_DSYNC), + * cannot be used with noncontiguous heaps */ +#define GRALLOC_USAGE_PRIVATE_UNCACHED 0x02000000 + +/* Buffer content should be displayed on an primary display only */ +#define GRALLOC_USAGE_PRIVATE_INTERNAL_ONLY 0x04000000 + +/* Buffer content should be displayed on an external display only */ +#define GRALLOC_USAGE_PRIVATE_EXTERNAL_ONLY 0x08000000 + +/* This flag is set for WFD usecase */ +#define GRALLOC_USAGE_PRIVATE_WFD 0x00200000 + +/* CAMERA heap is a carveout heap for camera, is not secured */ +#define GRALLOC_USAGE_PRIVATE_CAMERA_HEAP 0x00400000 + +/* This flag is used for SECURE display usecase */ +#define GRALLOC_USAGE_PRIVATE_SECURE_DISPLAY 0x00800000 + +/* define Gralloc perform */ +#define GRALLOC_MODULE_PERFORM_CREATE_HANDLE_FROM_BUFFER 1 +// This will be used by the graphics drivers to know if certain features +// are defined in this display HAL. +// Ex: Newer GFX libraries + Older Display HAL +#define GRALLOC_MODULE_PERFORM_GET_STRIDE 2 +#define GRALLOC_MODULE_PERFORM_GET_CUSTOM_STRIDE_FROM_HANDLE 3 +#define GRALLOC_MODULE_PERFORM_GET_CUSTOM_STRIDE_AND_HEIGHT_FROM_HANDLE 4 +#define GRALLOC_MODULE_PERFORM_GET_ATTRIBUTES 5 +#define GRALLOC_MODULE_PERFORM_GET_COLOR_SPACE_FROM_HANDLE 6 +#define GRALLOC_MODULE_PERFORM_GET_YUV_PLANE_INFO 7 +#define GRALLOC_MODULE_PERFORM_GET_MAP_SECURE_BUFFER_INFO 8 +#define GRALLOC_MODULE_PERFORM_GET_UBWC_FLAG 9 +#define GRALLOC_MODULE_PERFORM_GET_RGB_DATA_ADDRESS 10 +#define GRALLOC_MODULE_PERFORM_GET_IGC 11 +#define GRALLOC_MODULE_PERFORM_SET_IGC 12 +#define GRALLOC_MODULE_PERFORM_SET_SINGLE_BUFFER_MODE 13 + +/* OEM specific HAL formats */ + +#define HAL_PIXEL_FORMAT_RGBA_5551 6 +#define HAL_PIXEL_FORMAT_RGBA_4444 7 +#define HAL_PIXEL_FORMAT_NV12_ENCODEABLE 0x102 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_VENUS 0x7FA30C04 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_TILED 0x7FA30C03 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP 0x109 +#define HAL_PIXEL_FORMAT_YCrCb_420_SP_ADRENO 0x7FA30C01 +#define HAL_PIXEL_FORMAT_YCrCb_422_SP 0x10B +#define HAL_PIXEL_FORMAT_R_8 0x10D +#define HAL_PIXEL_FORMAT_RG_88 0x10E +#define HAL_PIXEL_FORMAT_YCbCr_444_SP 0x10F +#define HAL_PIXEL_FORMAT_YCrCb_444_SP 0x110 +#define HAL_PIXEL_FORMAT_YCrCb_422_I 0x111 +#define HAL_PIXEL_FORMAT_BGRX_8888 0x112 +#define HAL_PIXEL_FORMAT_NV21_ZSL 0x113 +#define HAL_PIXEL_FORMAT_YCrCb_420_SP_VENUS 0x114 +#define HAL_PIXEL_FORMAT_BGR_565 0x115 +#define HAL_PIXEL_FORMAT_INTERLACE 0x180 + +//v4l2_fourcc('Y', 'U', 'Y', 'L'). 24 bpp YUYV 4:2:2 10 bit per component +#define HAL_PIXEL_FORMAT_YCbCr_422_I_10BIT 0x4C595559 + +//v4l2_fourcc('Y', 'B', 'W', 'C'). 10 bit per component. This compressed +//format reduces the memory access bandwidth +#define HAL_PIXEL_FORMAT_YCbCr_422_I_10BIT_COMPRESSED 0x43574259 + +// UBWC aligned Venus format +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_VENUS_UBWC 0x7FA30C06 + +//Khronos ASTC formats +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_4x4_KHR 0x93B0 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_5x4_KHR 0x93B1 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_5x5_KHR 0x93B2 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_6x5_KHR 0x93B3 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_6x6_KHR 0x93B4 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x5_KHR 0x93B5 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x6_KHR 0x93B6 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x8_KHR 0x93B7 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x5_KHR 0x93B8 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x6_KHR 0x93B9 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x8_KHR 0x93BA +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x10_KHR 0x93BB +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_12x10_KHR 0x93BC +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_12x12_KHR 0x93BD +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_4x4_KHR 0x93D0 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_5x4_KHR 0x93D1 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_5x5_KHR 0x93D2 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_6x5_KHR 0x93D3 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_6x6_KHR 0x93D4 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x5_KHR 0x93D5 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x6_KHR 0x93D6 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x8_KHR 0x93D7 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x5_KHR 0x93D8 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x6_KHR 0x93D9 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x8_KHR 0x93DA +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x10_KHR 0x93DB +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_12x10_KHR 0x93DC +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_12x12_KHR 0x93DD + +/* possible values for inverse gamma correction */ +#define HAL_IGC_NOT_SPECIFIED 0 +#define HAL_IGC_s_RGB 1 + +/* possible formats for 3D content*/ +enum { + HAL_NO_3D = 0x0, + HAL_3D_SIDE_BY_SIDE_L_R = 0x1, + HAL_3D_SIDE_BY_SIDE_R_L = 0x2, + HAL_3D_TOP_BOTTOM = 0x4, + HAL_3D_IN_SIDE_BY_SIDE_L_R = 0x10000, //unused legacy format +}; + +enum { + BUFFER_TYPE_UI = 0, + BUFFER_TYPE_VIDEO +}; + +#ifdef __cplusplus +struct private_handle_t : public native_handle { +#else + struct private_handle_t { + native_handle_t nativeHandle; +#endif + enum { + PRIV_FLAGS_FRAMEBUFFER = 0x00000001, + PRIV_FLAGS_USES_ION = 0x00000008, + PRIV_FLAGS_USES_ASHMEM = 0x00000010, + PRIV_FLAGS_NEEDS_FLUSH = 0x00000020, + PRIV_FLAGS_INTERNAL_ONLY = 0x00000040, + PRIV_FLAGS_NON_CPU_WRITER = 0x00000080, + PRIV_FLAGS_NONCONTIGUOUS_MEM = 0x00000100, + PRIV_FLAGS_CACHED = 0x00000200, + PRIV_FLAGS_SECURE_BUFFER = 0x00000400, + // Display on external only + PRIV_FLAGS_EXTERNAL_ONLY = 0x00002000, + // Set by HWC for protected non secure buffers + PRIV_FLAGS_PROTECTED_BUFFER = 0x00004000, + PRIV_FLAGS_VIDEO_ENCODER = 0x00010000, + PRIV_FLAGS_CAMERA_WRITE = 0x00020000, + PRIV_FLAGS_CAMERA_READ = 0x00040000, + PRIV_FLAGS_HW_COMPOSER = 0x00080000, + PRIV_FLAGS_HW_TEXTURE = 0x00100000, + PRIV_FLAGS_ITU_R_601 = 0x00200000, //Unused from display + PRIV_FLAGS_ITU_R_601_FR = 0x00400000, //Unused from display + PRIV_FLAGS_ITU_R_709 = 0x00800000, //Unused from display + PRIV_FLAGS_SECURE_DISPLAY = 0x01000000, + // Buffer is rendered in Tile Format + PRIV_FLAGS_TILE_RENDERED = 0x02000000, + // Buffer rendered using CPU/SW renderer + PRIV_FLAGS_CPU_RENDERED = 0x04000000, + // Buffer is allocated with UBWC alignment + PRIV_FLAGS_UBWC_ALIGNED = 0x08000000, + // Buffer allocated will be consumed by SF/HWC + PRIV_FLAGS_DISP_CONSUMER = 0x10000000 + }; + + // file-descriptors + int fd; + int fd_metadata; // fd for the meta-data + // ints + int magic; + int flags; + unsigned int size; + unsigned int offset; + int bufferType; + uint64_t base __attribute__((aligned(8))); + unsigned int offset_metadata; + // The gpu address mapped into the mmu. + uint64_t gpuaddr __attribute__((aligned(8))); + int format; + int width; // specifies aligned width + int height; // specifies aligned height + int real_width; + int real_height; + uint64_t base_metadata __attribute__((aligned(8))); + +#ifdef __cplusplus + static const int sNumFds = 2; + static inline int sNumInts() { + return ((sizeof(private_handle_t) - sizeof(native_handle_t)) / + sizeof(int)) - sNumFds; + } + static const int sMagic = 'gmsm'; + + private_handle_t(int fd, unsigned int size, int flags, int bufferType, + int format, int aligned_width, int aligned_height, + int width, int height, int eFd = -1, + unsigned int eOffset = 0, uint64_t eBase = 0) : + fd(fd), fd_metadata(eFd), magic(sMagic), + flags(flags), size(size), offset(0), bufferType(bufferType), + base(0), offset_metadata(eOffset), gpuaddr(0), + format(format), width(aligned_width), height(aligned_height), + real_width(width), real_height(height), base_metadata(eBase) + { + version = (int) sizeof(native_handle); + numInts = sNumInts(); + numFds = sNumFds; + } + ~private_handle_t() { + magic = 0; + } + + static int validate(const native_handle* h) { + const private_handle_t* hnd = (const private_handle_t*)h; + if (!h || h->version != sizeof(native_handle) || + h->numInts != sNumInts() || h->numFds != sNumFds || + hnd->magic != sMagic) + { + ALOGD("Invalid gralloc handle (at %p): " + "ver(%d/%zu) ints(%d/%d) fds(%d/%d)" + "magic(%c%c%c%c/%c%c%c%c)", + h, + h ? h->version : -1, sizeof(native_handle), + h ? h->numInts : -1, sNumInts(), + h ? h->numFds : -1, sNumFds, + hnd ? (((hnd->magic >> 24) & 0xFF)? + ((hnd->magic >> 24) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 16) & 0xFF)? + ((hnd->magic >> 16) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 8) & 0xFF)? + ((hnd->magic >> 8) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 0) & 0xFF)? + ((hnd->magic >> 0) & 0xFF) : '-') : '?', + (sMagic >> 24) & 0xFF, + (sMagic >> 16) & 0xFF, + (sMagic >> 8) & 0xFF, + (sMagic >> 0) & 0xFF); + return -EINVAL; + } + return 0; + } + + static private_handle_t* dynamicCast(const native_handle* in) { + if (validate(in) == 0) { + return (private_handle_t*) in; + } + return NULL; + } +#endif + }; + +#endif /* GRALLOC_PRIV_H_ */ diff --git a/phonelibs/linux/include/msm_ion.h b/phonelibs/linux/include/msm_ion.h new file mode 100644 index 00000000000000..e41b3170fd438e --- /dev/null +++ b/phonelibs/linux/include/msm_ion.h @@ -0,0 +1,211 @@ +#ifndef _UAPI_MSM_ION_H +#define _UAPI_MSM_ION_H + +#include + +enum msm_ion_heap_types { + ION_HEAP_TYPE_MSM_START = ION_HEAP_TYPE_CUSTOM + 1, + ION_HEAP_TYPE_SECURE_DMA = ION_HEAP_TYPE_MSM_START, + ION_HEAP_TYPE_SYSTEM_SECURE, + ION_HEAP_TYPE_HYP_CMA, + /* + * if you add a heap type here you should also add it to + * heap_types_info[] in msm_ion.c + */ +}; + +/** + * These are the only ids that should be used for Ion heap ids. + * The ids listed are the order in which allocation will be attempted + * if specified. Don't swap the order of heap ids unless you know what + * you are doing! + * Id's are spaced by purpose to allow new Id's to be inserted in-between (for + * possible fallbacks) + */ + +enum ion_heap_ids { + INVALID_HEAP_ID = -1, + ION_CP_MM_HEAP_ID = 8, + ION_SECURE_HEAP_ID = 9, + ION_SECURE_DISPLAY_HEAP_ID = 10, + ION_CP_MFC_HEAP_ID = 12, + ION_CP_WB_HEAP_ID = 16, /* 8660 only */ + ION_CAMERA_HEAP_ID = 20, /* 8660 only */ + ION_SYSTEM_CONTIG_HEAP_ID = 21, + ION_ADSP_HEAP_ID = 22, + ION_PIL1_HEAP_ID = 23, /* Currently used for other PIL images */ + ION_SF_HEAP_ID = 24, + ION_SYSTEM_HEAP_ID = 25, + ION_PIL2_HEAP_ID = 26, /* Currently used for modem firmware images */ + ION_QSECOM_HEAP_ID = 27, + ION_AUDIO_HEAP_ID = 28, + + ION_MM_FIRMWARE_HEAP_ID = 29, + + ION_HEAP_ID_RESERVED = 31 /** Bit reserved for ION_FLAG_SECURE flag */ +}; + +/* + * The IOMMU heap is deprecated! Here are some aliases for backwards + * compatibility: + */ +#define ION_IOMMU_HEAP_ID ION_SYSTEM_HEAP_ID +#define ION_HEAP_TYPE_IOMMU ION_HEAP_TYPE_SYSTEM + +enum ion_fixed_position { + NOT_FIXED, + FIXED_LOW, + FIXED_MIDDLE, + FIXED_HIGH, +}; + +enum cp_mem_usage { + VIDEO_BITSTREAM = 0x1, + VIDEO_PIXEL = 0x2, + VIDEO_NONPIXEL = 0x3, + DISPLAY_SECURE_CP_USAGE = 0x4, + CAMERA_SECURE_CP_USAGE = 0x5, + MAX_USAGE = 0x6, + UNKNOWN = 0x7FFFFFFF, +}; + +/** + * Flags to be used when allocating from the secure heap for + * content protection + */ +#define ION_FLAG_CP_TOUCH (1 << 17) +#define ION_FLAG_CP_BITSTREAM (1 << 18) +#define ION_FLAG_CP_PIXEL (1 << 19) +#define ION_FLAG_CP_NON_PIXEL (1 << 20) +#define ION_FLAG_CP_CAMERA (1 << 21) +#define ION_FLAG_CP_HLOS (1 << 22) +#define ION_FLAG_CP_HLOS_FREE (1 << 23) +#define ION_FLAG_CP_SEC_DISPLAY (1 << 25) +#define ION_FLAG_CP_APP (1 << 26) + +/** + * Flag to allow non continguous allocation of memory from secure + * heap + */ +#define ION_FLAG_ALLOW_NON_CONTIG (1 << 24) + +/** + * Flag to use when allocating to indicate that a heap is secure. + */ +#define ION_FLAG_SECURE (1 << ION_HEAP_ID_RESERVED) + +/** + * Flag for clients to force contiguous memort allocation + * + * Use of this flag is carefully monitored! + */ +#define ION_FLAG_FORCE_CONTIGUOUS (1 << 30) + +/* + * Used in conjunction with heap which pool memory to force an allocation + * to come from the page allocator directly instead of from the pool allocation + */ +#define ION_FLAG_POOL_FORCE_ALLOC (1 << 16) + + +#define ION_FLAG_POOL_PREFETCH (1 << 27) + +/** +* Deprecated! Please use the corresponding ION_FLAG_* +*/ +#define ION_SECURE ION_FLAG_SECURE +#define ION_FORCE_CONTIGUOUS ION_FLAG_FORCE_CONTIGUOUS + +/** + * Macro should be used with ion_heap_ids defined above. + */ +#define ION_HEAP(bit) (1 << (bit)) + +#define ION_ADSP_HEAP_NAME "adsp" +#define ION_SYSTEM_HEAP_NAME "system" +#define ION_VMALLOC_HEAP_NAME ION_SYSTEM_HEAP_NAME +#define ION_KMALLOC_HEAP_NAME "kmalloc" +#define ION_AUDIO_HEAP_NAME "audio" +#define ION_SF_HEAP_NAME "sf" +#define ION_MM_HEAP_NAME "mm" +#define ION_CAMERA_HEAP_NAME "camera_preview" +#define ION_IOMMU_HEAP_NAME "iommu" +#define ION_MFC_HEAP_NAME "mfc" +#define ION_WB_HEAP_NAME "wb" +#define ION_MM_FIRMWARE_HEAP_NAME "mm_fw" +#define ION_PIL1_HEAP_NAME "pil_1" +#define ION_PIL2_HEAP_NAME "pil_2" +#define ION_QSECOM_HEAP_NAME "qsecom" +#define ION_SECURE_HEAP_NAME "secure_heap" +#define ION_SECURE_DISPLAY_HEAP_NAME "secure_display" + +#define ION_SET_CACHED(__cache) (__cache | ION_FLAG_CACHED) +#define ION_SET_UNCACHED(__cache) (__cache & ~ION_FLAG_CACHED) + +#define ION_IS_CACHED(__flags) ((__flags) & ION_FLAG_CACHED) + +/* struct ion_flush_data - data passed to ion for flushing caches + * + * @handle: handle with data to flush + * @fd: fd to flush + * @vaddr: userspace virtual address mapped with mmap + * @offset: offset into the handle to flush + * @length: length of handle to flush + * + * Performs cache operations on the handle. If p is the start address + * of the handle, p + offset through p + offset + length will have + * the cache operations performed + */ +struct ion_flush_data { + ion_user_handle_t handle; + int fd; + void *vaddr; + unsigned int offset; + unsigned int length; +}; + +struct ion_prefetch_regions { + unsigned int vmid; + size_t __user *sizes; + unsigned int nr_sizes; +}; + +struct ion_prefetch_data { + int heap_id; + unsigned long len; + /* Is unsigned long bad? 32bit compiler vs 64 bit compiler*/ + struct ion_prefetch_regions __user *regions; + unsigned int nr_regions; +}; + +#define ION_IOC_MSM_MAGIC 'M' + +/** + * DOC: ION_IOC_CLEAN_CACHES - clean the caches + * + * Clean the caches of the handle specified. + */ +#define ION_IOC_CLEAN_CACHES _IOWR(ION_IOC_MSM_MAGIC, 0, \ + struct ion_flush_data) +/** + * DOC: ION_IOC_INV_CACHES - invalidate the caches + * + * Invalidate the caches of the handle specified. + */ +#define ION_IOC_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 1, \ + struct ion_flush_data) +/** + * DOC: ION_IOC_CLEAN_INV_CACHES - clean and invalidate the caches + * + * Clean and invalidate the caches of the handle specified. + */ +#define ION_IOC_CLEAN_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 2, \ + struct ion_flush_data) + +#define ION_IOC_PREFETCH _IOWR(ION_IOC_MSM_MAGIC, 3, \ + struct ion_prefetch_data) + +#define ION_IOC_DRAIN _IOWR(ION_IOC_MSM_MAGIC, 4, \ + struct ion_prefetch_data) + +#endif diff --git a/phonelibs/opencl/include/CL/cl.h b/phonelibs/opencl/include/CL/cl.h new file mode 100644 index 00000000000000..0086319f5faf1b --- /dev/null +++ b/phonelibs/opencl/include/CL/cl.h @@ -0,0 +1,1452 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +#ifndef __OPENCL_CL_H +#define __OPENCL_CL_H + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/******************************************************************************/ + +typedef struct _cl_platform_id * cl_platform_id; +typedef struct _cl_device_id * cl_device_id; +typedef struct _cl_context * cl_context; +typedef struct _cl_command_queue * cl_command_queue; +typedef struct _cl_mem * cl_mem; +typedef struct _cl_program * cl_program; +typedef struct _cl_kernel * cl_kernel; +typedef struct _cl_event * cl_event; +typedef struct _cl_sampler * cl_sampler; + +typedef cl_uint cl_bool; /* WARNING! Unlike cl_ types in cl_platform.h, cl_bool is not guaranteed to be the same size as the bool in kernels. */ +typedef cl_ulong cl_bitfield; +typedef cl_bitfield cl_device_type; +typedef cl_uint cl_platform_info; +typedef cl_uint cl_device_info; +typedef cl_bitfield cl_device_fp_config; +typedef cl_uint cl_device_mem_cache_type; +typedef cl_uint cl_device_local_mem_type; +typedef cl_bitfield cl_device_exec_capabilities; +typedef cl_bitfield cl_device_svm_capabilities; +typedef cl_bitfield cl_command_queue_properties; +typedef intptr_t cl_device_partition_property; +typedef cl_bitfield cl_device_affinity_domain; + +typedef intptr_t cl_context_properties; +typedef cl_uint cl_context_info; +typedef cl_bitfield cl_queue_properties; +typedef cl_uint cl_command_queue_info; +typedef cl_uint cl_channel_order; +typedef cl_uint cl_channel_type; +typedef cl_bitfield cl_mem_flags; +typedef cl_bitfield cl_svm_mem_flags; +typedef cl_uint cl_mem_object_type; +typedef cl_uint cl_mem_info; +typedef cl_bitfield cl_mem_migration_flags; +typedef cl_uint cl_image_info; +typedef cl_uint cl_buffer_create_type; +typedef cl_uint cl_addressing_mode; +typedef cl_uint cl_filter_mode; +typedef cl_uint cl_sampler_info; +typedef cl_bitfield cl_map_flags; +typedef intptr_t cl_pipe_properties; +typedef cl_uint cl_pipe_info; +typedef cl_uint cl_program_info; +typedef cl_uint cl_program_build_info; +typedef cl_uint cl_program_binary_type; +typedef cl_int cl_build_status; +typedef cl_uint cl_kernel_info; +typedef cl_uint cl_kernel_arg_info; +typedef cl_uint cl_kernel_arg_address_qualifier; +typedef cl_uint cl_kernel_arg_access_qualifier; +typedef cl_bitfield cl_kernel_arg_type_qualifier; +typedef cl_uint cl_kernel_work_group_info; +typedef cl_uint cl_kernel_sub_group_info; +typedef cl_uint cl_event_info; +typedef cl_uint cl_command_type; +typedef cl_uint cl_profiling_info; +typedef cl_bitfield cl_sampler_properties; +typedef cl_uint cl_kernel_exec_info; + +typedef struct _cl_image_format { + cl_channel_order image_channel_order; + cl_channel_type image_channel_data_type; +} cl_image_format; + +typedef struct _cl_image_desc { + cl_mem_object_type image_type; + size_t image_width; + size_t image_height; + size_t image_depth; + size_t image_array_size; + size_t image_row_pitch; + size_t image_slice_pitch; + cl_uint num_mip_levels; + cl_uint num_samples; +#ifdef __GNUC__ + __extension__ /* Prevents warnings about anonymous union in -pedantic builds */ +#endif + union { + cl_mem buffer; + cl_mem mem_object; + }; +} cl_image_desc; + +typedef struct _cl_buffer_region { + size_t origin; + size_t size; +} cl_buffer_region; + + +/******************************************************************************/ + +/* Error Codes */ +#define CL_SUCCESS 0 +#define CL_DEVICE_NOT_FOUND -1 +#define CL_DEVICE_NOT_AVAILABLE -2 +#define CL_COMPILER_NOT_AVAILABLE -3 +#define CL_MEM_OBJECT_ALLOCATION_FAILURE -4 +#define CL_OUT_OF_RESOURCES -5 +#define CL_OUT_OF_HOST_MEMORY -6 +#define CL_PROFILING_INFO_NOT_AVAILABLE -7 +#define CL_MEM_COPY_OVERLAP -8 +#define CL_IMAGE_FORMAT_MISMATCH -9 +#define CL_IMAGE_FORMAT_NOT_SUPPORTED -10 +#define CL_BUILD_PROGRAM_FAILURE -11 +#define CL_MAP_FAILURE -12 +#define CL_MISALIGNED_SUB_BUFFER_OFFSET -13 +#define CL_EXEC_STATUS_ERROR_FOR_EVENTS_IN_WAIT_LIST -14 +#define CL_COMPILE_PROGRAM_FAILURE -15 +#define CL_LINKER_NOT_AVAILABLE -16 +#define CL_LINK_PROGRAM_FAILURE -17 +#define CL_DEVICE_PARTITION_FAILED -18 +#define CL_KERNEL_ARG_INFO_NOT_AVAILABLE -19 + +#define CL_INVALID_VALUE -30 +#define CL_INVALID_DEVICE_TYPE -31 +#define CL_INVALID_PLATFORM -32 +#define CL_INVALID_DEVICE -33 +#define CL_INVALID_CONTEXT -34 +#define CL_INVALID_QUEUE_PROPERTIES -35 +#define CL_INVALID_COMMAND_QUEUE -36 +#define CL_INVALID_HOST_PTR -37 +#define CL_INVALID_MEM_OBJECT -38 +#define CL_INVALID_IMAGE_FORMAT_DESCRIPTOR -39 +#define CL_INVALID_IMAGE_SIZE -40 +#define CL_INVALID_SAMPLER -41 +#define CL_INVALID_BINARY -42 +#define CL_INVALID_BUILD_OPTIONS -43 +#define CL_INVALID_PROGRAM -44 +#define CL_INVALID_PROGRAM_EXECUTABLE -45 +#define CL_INVALID_KERNEL_NAME -46 +#define CL_INVALID_KERNEL_DEFINITION -47 +#define CL_INVALID_KERNEL -48 +#define CL_INVALID_ARG_INDEX -49 +#define CL_INVALID_ARG_VALUE -50 +#define CL_INVALID_ARG_SIZE -51 +#define CL_INVALID_KERNEL_ARGS -52 +#define CL_INVALID_WORK_DIMENSION -53 +#define CL_INVALID_WORK_GROUP_SIZE -54 +#define CL_INVALID_WORK_ITEM_SIZE -55 +#define CL_INVALID_GLOBAL_OFFSET -56 +#define CL_INVALID_EVENT_WAIT_LIST -57 +#define CL_INVALID_EVENT -58 +#define CL_INVALID_OPERATION -59 +#define CL_INVALID_GL_OBJECT -60 +#define CL_INVALID_BUFFER_SIZE -61 +#define CL_INVALID_MIP_LEVEL -62 +#define CL_INVALID_GLOBAL_WORK_SIZE -63 +#define CL_INVALID_PROPERTY -64 +#define CL_INVALID_IMAGE_DESCRIPTOR -65 +#define CL_INVALID_COMPILER_OPTIONS -66 +#define CL_INVALID_LINKER_OPTIONS -67 +#define CL_INVALID_DEVICE_PARTITION_COUNT -68 +#define CL_INVALID_PIPE_SIZE -69 +#define CL_INVALID_DEVICE_QUEUE -70 + +/* OpenCL Version */ +#define CL_VERSION_1_0 1 +#define CL_VERSION_1_1 1 +#define CL_VERSION_1_2 1 +#define CL_VERSION_2_0 1 +#define CL_VERSION_2_1 1 + +/* cl_bool */ +#define CL_FALSE 0 +#define CL_TRUE 1 +#define CL_BLOCKING CL_TRUE +#define CL_NON_BLOCKING CL_FALSE + +/* cl_platform_info */ +#define CL_PLATFORM_PROFILE 0x0900 +#define CL_PLATFORM_VERSION 0x0901 +#define CL_PLATFORM_NAME 0x0902 +#define CL_PLATFORM_VENDOR 0x0903 +#define CL_PLATFORM_EXTENSIONS 0x0904 +#define CL_PLATFORM_HOST_TIMER_RESOLUTION 0x0905 + +/* cl_device_type - bitfield */ +#define CL_DEVICE_TYPE_DEFAULT (1 << 0) +#define CL_DEVICE_TYPE_CPU (1 << 1) +#define CL_DEVICE_TYPE_GPU (1 << 2) +#define CL_DEVICE_TYPE_ACCELERATOR (1 << 3) +#define CL_DEVICE_TYPE_CUSTOM (1 << 4) +#define CL_DEVICE_TYPE_ALL 0xFFFFFFFF + +/* cl_device_info */ +#define CL_DEVICE_TYPE 0x1000 +#define CL_DEVICE_VENDOR_ID 0x1001 +#define CL_DEVICE_MAX_COMPUTE_UNITS 0x1002 +#define CL_DEVICE_MAX_WORK_ITEM_DIMENSIONS 0x1003 +#define CL_DEVICE_MAX_WORK_GROUP_SIZE 0x1004 +#define CL_DEVICE_MAX_WORK_ITEM_SIZES 0x1005 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_CHAR 0x1006 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_SHORT 0x1007 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_INT 0x1008 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_LONG 0x1009 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_FLOAT 0x100A +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_DOUBLE 0x100B +#define CL_DEVICE_MAX_CLOCK_FREQUENCY 0x100C +#define CL_DEVICE_ADDRESS_BITS 0x100D +#define CL_DEVICE_MAX_READ_IMAGE_ARGS 0x100E +#define CL_DEVICE_MAX_WRITE_IMAGE_ARGS 0x100F +#define CL_DEVICE_MAX_MEM_ALLOC_SIZE 0x1010 +#define CL_DEVICE_IMAGE2D_MAX_WIDTH 0x1011 +#define CL_DEVICE_IMAGE2D_MAX_HEIGHT 0x1012 +#define CL_DEVICE_IMAGE3D_MAX_WIDTH 0x1013 +#define CL_DEVICE_IMAGE3D_MAX_HEIGHT 0x1014 +#define CL_DEVICE_IMAGE3D_MAX_DEPTH 0x1015 +#define CL_DEVICE_IMAGE_SUPPORT 0x1016 +#define CL_DEVICE_MAX_PARAMETER_SIZE 0x1017 +#define CL_DEVICE_MAX_SAMPLERS 0x1018 +#define CL_DEVICE_MEM_BASE_ADDR_ALIGN 0x1019 +#define CL_DEVICE_MIN_DATA_TYPE_ALIGN_SIZE 0x101A +#define CL_DEVICE_SINGLE_FP_CONFIG 0x101B +#define CL_DEVICE_GLOBAL_MEM_CACHE_TYPE 0x101C +#define CL_DEVICE_GLOBAL_MEM_CACHELINE_SIZE 0x101D +#define CL_DEVICE_GLOBAL_MEM_CACHE_SIZE 0x101E +#define CL_DEVICE_GLOBAL_MEM_SIZE 0x101F +#define CL_DEVICE_MAX_CONSTANT_BUFFER_SIZE 0x1020 +#define CL_DEVICE_MAX_CONSTANT_ARGS 0x1021 +#define CL_DEVICE_LOCAL_MEM_TYPE 0x1022 +#define CL_DEVICE_LOCAL_MEM_SIZE 0x1023 +#define CL_DEVICE_ERROR_CORRECTION_SUPPORT 0x1024 +#define CL_DEVICE_PROFILING_TIMER_RESOLUTION 0x1025 +#define CL_DEVICE_ENDIAN_LITTLE 0x1026 +#define CL_DEVICE_AVAILABLE 0x1027 +#define CL_DEVICE_COMPILER_AVAILABLE 0x1028 +#define CL_DEVICE_EXECUTION_CAPABILITIES 0x1029 +#define CL_DEVICE_QUEUE_PROPERTIES 0x102A /* deprecated */ +#define CL_DEVICE_QUEUE_ON_HOST_PROPERTIES 0x102A +#define CL_DEVICE_NAME 0x102B +#define CL_DEVICE_VENDOR 0x102C +#define CL_DRIVER_VERSION 0x102D +#define CL_DEVICE_PROFILE 0x102E +#define CL_DEVICE_VERSION 0x102F +#define CL_DEVICE_EXTENSIONS 0x1030 +#define CL_DEVICE_PLATFORM 0x1031 +#define CL_DEVICE_DOUBLE_FP_CONFIG 0x1032 +/* 0x1033 reserved for CL_DEVICE_HALF_FP_CONFIG */ +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_HALF 0x1034 +#define CL_DEVICE_HOST_UNIFIED_MEMORY 0x1035 /* deprecated */ +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_CHAR 0x1036 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_SHORT 0x1037 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_INT 0x1038 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_LONG 0x1039 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_FLOAT 0x103A +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_DOUBLE 0x103B +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_HALF 0x103C +#define CL_DEVICE_OPENCL_C_VERSION 0x103D +#define CL_DEVICE_LINKER_AVAILABLE 0x103E +#define CL_DEVICE_BUILT_IN_KERNELS 0x103F +#define CL_DEVICE_IMAGE_MAX_BUFFER_SIZE 0x1040 +#define CL_DEVICE_IMAGE_MAX_ARRAY_SIZE 0x1041 +#define CL_DEVICE_PARENT_DEVICE 0x1042 +#define CL_DEVICE_PARTITION_MAX_SUB_DEVICES 0x1043 +#define CL_DEVICE_PARTITION_PROPERTIES 0x1044 +#define CL_DEVICE_PARTITION_AFFINITY_DOMAIN 0x1045 +#define CL_DEVICE_PARTITION_TYPE 0x1046 +#define CL_DEVICE_REFERENCE_COUNT 0x1047 +#define CL_DEVICE_PREFERRED_INTEROP_USER_SYNC 0x1048 +#define CL_DEVICE_PRINTF_BUFFER_SIZE 0x1049 +#define CL_DEVICE_IMAGE_PITCH_ALIGNMENT 0x104A +#define CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT 0x104B +#define CL_DEVICE_MAX_READ_WRITE_IMAGE_ARGS 0x104C +#define CL_DEVICE_MAX_GLOBAL_VARIABLE_SIZE 0x104D +#define CL_DEVICE_QUEUE_ON_DEVICE_PROPERTIES 0x104E +#define CL_DEVICE_QUEUE_ON_DEVICE_PREFERRED_SIZE 0x104F +#define CL_DEVICE_QUEUE_ON_DEVICE_MAX_SIZE 0x1050 +#define CL_DEVICE_MAX_ON_DEVICE_QUEUES 0x1051 +#define CL_DEVICE_MAX_ON_DEVICE_EVENTS 0x1052 +#define CL_DEVICE_SVM_CAPABILITIES 0x1053 +#define CL_DEVICE_GLOBAL_VARIABLE_PREFERRED_TOTAL_SIZE 0x1054 +#define CL_DEVICE_MAX_PIPE_ARGS 0x1055 +#define CL_DEVICE_PIPE_MAX_ACTIVE_RESERVATIONS 0x1056 +#define CL_DEVICE_PIPE_MAX_PACKET_SIZE 0x1057 +#define CL_DEVICE_PREFERRED_PLATFORM_ATOMIC_ALIGNMENT 0x1058 +#define CL_DEVICE_PREFERRED_GLOBAL_ATOMIC_ALIGNMENT 0x1059 +#define CL_DEVICE_PREFERRED_LOCAL_ATOMIC_ALIGNMENT 0x105A +#define CL_DEVICE_IL_VERSION 0x105B +#define CL_DEVICE_MAX_NUM_SUB_GROUPS 0x105C +#define CL_DEVICE_SUB_GROUP_INDEPENDENT_FORWARD_PROGRESS 0x105D + +/* cl_device_fp_config - bitfield */ +#define CL_FP_DENORM (1 << 0) +#define CL_FP_INF_NAN (1 << 1) +#define CL_FP_ROUND_TO_NEAREST (1 << 2) +#define CL_FP_ROUND_TO_ZERO (1 << 3) +#define CL_FP_ROUND_TO_INF (1 << 4) +#define CL_FP_FMA (1 << 5) +#define CL_FP_SOFT_FLOAT (1 << 6) +#define CL_FP_CORRECTLY_ROUNDED_DIVIDE_SQRT (1 << 7) + +/* cl_device_mem_cache_type */ +#define CL_NONE 0x0 +#define CL_READ_ONLY_CACHE 0x1 +#define CL_READ_WRITE_CACHE 0x2 + +/* cl_device_local_mem_type */ +#define CL_LOCAL 0x1 +#define CL_GLOBAL 0x2 + +/* cl_device_exec_capabilities - bitfield */ +#define CL_EXEC_KERNEL (1 << 0) +#define CL_EXEC_NATIVE_KERNEL (1 << 1) + +/* cl_command_queue_properties - bitfield */ +#define CL_QUEUE_OUT_OF_ORDER_EXEC_MODE_ENABLE (1 << 0) +#define CL_QUEUE_PROFILING_ENABLE (1 << 1) +#define CL_QUEUE_ON_DEVICE (1 << 2) +#define CL_QUEUE_ON_DEVICE_DEFAULT (1 << 3) + +/* cl_context_info */ +#define CL_CONTEXT_REFERENCE_COUNT 0x1080 +#define CL_CONTEXT_DEVICES 0x1081 +#define CL_CONTEXT_PROPERTIES 0x1082 +#define CL_CONTEXT_NUM_DEVICES 0x1083 + +/* cl_context_properties */ +#define CL_CONTEXT_PLATFORM 0x1084 +#define CL_CONTEXT_INTEROP_USER_SYNC 0x1085 + +/* cl_device_partition_property */ +#define CL_DEVICE_PARTITION_EQUALLY 0x1086 +#define CL_DEVICE_PARTITION_BY_COUNTS 0x1087 +#define CL_DEVICE_PARTITION_BY_COUNTS_LIST_END 0x0 +#define CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN 0x1088 + +/* cl_device_affinity_domain */ +#define CL_DEVICE_AFFINITY_DOMAIN_NUMA (1 << 0) +#define CL_DEVICE_AFFINITY_DOMAIN_L4_CACHE (1 << 1) +#define CL_DEVICE_AFFINITY_DOMAIN_L3_CACHE (1 << 2) +#define CL_DEVICE_AFFINITY_DOMAIN_L2_CACHE (1 << 3) +#define CL_DEVICE_AFFINITY_DOMAIN_L1_CACHE (1 << 4) +#define CL_DEVICE_AFFINITY_DOMAIN_NEXT_PARTITIONABLE (1 << 5) + +/* cl_device_svm_capabilities */ +#define CL_DEVICE_SVM_COARSE_GRAIN_BUFFER (1 << 0) +#define CL_DEVICE_SVM_FINE_GRAIN_BUFFER (1 << 1) +#define CL_DEVICE_SVM_FINE_GRAIN_SYSTEM (1 << 2) +#define CL_DEVICE_SVM_ATOMICS (1 << 3) + +/* cl_command_queue_info */ +#define CL_QUEUE_CONTEXT 0x1090 +#define CL_QUEUE_DEVICE 0x1091 +#define CL_QUEUE_REFERENCE_COUNT 0x1092 +#define CL_QUEUE_PROPERTIES 0x1093 +#define CL_QUEUE_SIZE 0x1094 +#define CL_QUEUE_DEVICE_DEFAULT 0x1095 + +/* cl_mem_flags and cl_svm_mem_flags - bitfield */ +#define CL_MEM_READ_WRITE (1 << 0) +#define CL_MEM_WRITE_ONLY (1 << 1) +#define CL_MEM_READ_ONLY (1 << 2) +#define CL_MEM_USE_HOST_PTR (1 << 3) +#define CL_MEM_ALLOC_HOST_PTR (1 << 4) +#define CL_MEM_COPY_HOST_PTR (1 << 5) +/* reserved (1 << 6) */ +#define CL_MEM_HOST_WRITE_ONLY (1 << 7) +#define CL_MEM_HOST_READ_ONLY (1 << 8) +#define CL_MEM_HOST_NO_ACCESS (1 << 9) +#define CL_MEM_SVM_FINE_GRAIN_BUFFER (1 << 10) /* used by cl_svm_mem_flags only */ +#define CL_MEM_SVM_ATOMICS (1 << 11) /* used by cl_svm_mem_flags only */ +#define CL_MEM_KERNEL_READ_AND_WRITE (1 << 12) + +/* cl_mem_migration_flags - bitfield */ +#define CL_MIGRATE_MEM_OBJECT_HOST (1 << 0) +#define CL_MIGRATE_MEM_OBJECT_CONTENT_UNDEFINED (1 << 1) + +/* cl_channel_order */ +#define CL_R 0x10B0 +#define CL_A 0x10B1 +#define CL_RG 0x10B2 +#define CL_RA 0x10B3 +#define CL_RGB 0x10B4 +#define CL_RGBA 0x10B5 +#define CL_BGRA 0x10B6 +#define CL_ARGB 0x10B7 +#define CL_INTENSITY 0x10B8 +#define CL_LUMINANCE 0x10B9 +#define CL_Rx 0x10BA +#define CL_RGx 0x10BB +#define CL_RGBx 0x10BC +#define CL_DEPTH 0x10BD +#define CL_DEPTH_STENCIL 0x10BE +#define CL_sRGB 0x10BF +#define CL_sRGBx 0x10C0 +#define CL_sRGBA 0x10C1 +#define CL_sBGRA 0x10C2 +#define CL_ABGR 0x10C3 + +/* cl_channel_type */ +#define CL_SNORM_INT8 0x10D0 +#define CL_SNORM_INT16 0x10D1 +#define CL_UNORM_INT8 0x10D2 +#define CL_UNORM_INT16 0x10D3 +#define CL_UNORM_SHORT_565 0x10D4 +#define CL_UNORM_SHORT_555 0x10D5 +#define CL_UNORM_INT_101010 0x10D6 +#define CL_SIGNED_INT8 0x10D7 +#define CL_SIGNED_INT16 0x10D8 +#define CL_SIGNED_INT32 0x10D9 +#define CL_UNSIGNED_INT8 0x10DA +#define CL_UNSIGNED_INT16 0x10DB +#define CL_UNSIGNED_INT32 0x10DC +#define CL_HALF_FLOAT 0x10DD +#define CL_FLOAT 0x10DE +#define CL_UNORM_INT24 0x10DF +#define CL_UNORM_INT_101010_2 0x10E0 + +/* cl_mem_object_type */ +#define CL_MEM_OBJECT_BUFFER 0x10F0 +#define CL_MEM_OBJECT_IMAGE2D 0x10F1 +#define CL_MEM_OBJECT_IMAGE3D 0x10F2 +#define CL_MEM_OBJECT_IMAGE2D_ARRAY 0x10F3 +#define CL_MEM_OBJECT_IMAGE1D 0x10F4 +#define CL_MEM_OBJECT_IMAGE1D_ARRAY 0x10F5 +#define CL_MEM_OBJECT_IMAGE1D_BUFFER 0x10F6 +#define CL_MEM_OBJECT_PIPE 0x10F7 + +/* cl_mem_info */ +#define CL_MEM_TYPE 0x1100 +#define CL_MEM_FLAGS 0x1101 +#define CL_MEM_SIZE 0x1102 +#define CL_MEM_HOST_PTR 0x1103 +#define CL_MEM_MAP_COUNT 0x1104 +#define CL_MEM_REFERENCE_COUNT 0x1105 +#define CL_MEM_CONTEXT 0x1106 +#define CL_MEM_ASSOCIATED_MEMOBJECT 0x1107 +#define CL_MEM_OFFSET 0x1108 +#define CL_MEM_USES_SVM_POINTER 0x1109 + +/* cl_image_info */ +#define CL_IMAGE_FORMAT 0x1110 +#define CL_IMAGE_ELEMENT_SIZE 0x1111 +#define CL_IMAGE_ROW_PITCH 0x1112 +#define CL_IMAGE_SLICE_PITCH 0x1113 +#define CL_IMAGE_WIDTH 0x1114 +#define CL_IMAGE_HEIGHT 0x1115 +#define CL_IMAGE_DEPTH 0x1116 +#define CL_IMAGE_ARRAY_SIZE 0x1117 +#define CL_IMAGE_BUFFER 0x1118 +#define CL_IMAGE_NUM_MIP_LEVELS 0x1119 +#define CL_IMAGE_NUM_SAMPLES 0x111A + +/* cl_pipe_info */ +#define CL_PIPE_PACKET_SIZE 0x1120 +#define CL_PIPE_MAX_PACKETS 0x1121 + +/* cl_addressing_mode */ +#define CL_ADDRESS_NONE 0x1130 +#define CL_ADDRESS_CLAMP_TO_EDGE 0x1131 +#define CL_ADDRESS_CLAMP 0x1132 +#define CL_ADDRESS_REPEAT 0x1133 +#define CL_ADDRESS_MIRRORED_REPEAT 0x1134 + +/* cl_filter_mode */ +#define CL_FILTER_NEAREST 0x1140 +#define CL_FILTER_LINEAR 0x1141 + +/* cl_sampler_info */ +#define CL_SAMPLER_REFERENCE_COUNT 0x1150 +#define CL_SAMPLER_CONTEXT 0x1151 +#define CL_SAMPLER_NORMALIZED_COORDS 0x1152 +#define CL_SAMPLER_ADDRESSING_MODE 0x1153 +#define CL_SAMPLER_FILTER_MODE 0x1154 +#define CL_SAMPLER_MIP_FILTER_MODE 0x1155 +#define CL_SAMPLER_LOD_MIN 0x1156 +#define CL_SAMPLER_LOD_MAX 0x1157 + +/* cl_map_flags - bitfield */ +#define CL_MAP_READ (1 << 0) +#define CL_MAP_WRITE (1 << 1) +#define CL_MAP_WRITE_INVALIDATE_REGION (1 << 2) + +/* cl_program_info */ +#define CL_PROGRAM_REFERENCE_COUNT 0x1160 +#define CL_PROGRAM_CONTEXT 0x1161 +#define CL_PROGRAM_NUM_DEVICES 0x1162 +#define CL_PROGRAM_DEVICES 0x1163 +#define CL_PROGRAM_SOURCE 0x1164 +#define CL_PROGRAM_BINARY_SIZES 0x1165 +#define CL_PROGRAM_BINARIES 0x1166 +#define CL_PROGRAM_NUM_KERNELS 0x1167 +#define CL_PROGRAM_KERNEL_NAMES 0x1168 +#define CL_PROGRAM_IL 0x1169 + +/* cl_program_build_info */ +#define CL_PROGRAM_BUILD_STATUS 0x1181 +#define CL_PROGRAM_BUILD_OPTIONS 0x1182 +#define CL_PROGRAM_BUILD_LOG 0x1183 +#define CL_PROGRAM_BINARY_TYPE 0x1184 +#define CL_PROGRAM_BUILD_GLOBAL_VARIABLE_TOTAL_SIZE 0x1185 + +/* cl_program_binary_type */ +#define CL_PROGRAM_BINARY_TYPE_NONE 0x0 +#define CL_PROGRAM_BINARY_TYPE_COMPILED_OBJECT 0x1 +#define CL_PROGRAM_BINARY_TYPE_LIBRARY 0x2 +#define CL_PROGRAM_BINARY_TYPE_EXECUTABLE 0x4 + +/* cl_build_status */ +#define CL_BUILD_SUCCESS 0 +#define CL_BUILD_NONE -1 +#define CL_BUILD_ERROR -2 +#define CL_BUILD_IN_PROGRESS -3 + +/* cl_kernel_info */ +#define CL_KERNEL_FUNCTION_NAME 0x1190 +#define CL_KERNEL_NUM_ARGS 0x1191 +#define CL_KERNEL_REFERENCE_COUNT 0x1192 +#define CL_KERNEL_CONTEXT 0x1193 +#define CL_KERNEL_PROGRAM 0x1194 +#define CL_KERNEL_ATTRIBUTES 0x1195 +#define CL_KERNEL_MAX_NUM_SUB_GROUPS 0x11B9 +#define CL_KERNEL_COMPILE_NUM_SUB_GROUPS 0x11BA + +/* cl_kernel_arg_info */ +#define CL_KERNEL_ARG_ADDRESS_QUALIFIER 0x1196 +#define CL_KERNEL_ARG_ACCESS_QUALIFIER 0x1197 +#define CL_KERNEL_ARG_TYPE_NAME 0x1198 +#define CL_KERNEL_ARG_TYPE_QUALIFIER 0x1199 +#define CL_KERNEL_ARG_NAME 0x119A + +/* cl_kernel_arg_address_qualifier */ +#define CL_KERNEL_ARG_ADDRESS_GLOBAL 0x119B +#define CL_KERNEL_ARG_ADDRESS_LOCAL 0x119C +#define CL_KERNEL_ARG_ADDRESS_CONSTANT 0x119D +#define CL_KERNEL_ARG_ADDRESS_PRIVATE 0x119E + +/* cl_kernel_arg_access_qualifier */ +#define CL_KERNEL_ARG_ACCESS_READ_ONLY 0x11A0 +#define CL_KERNEL_ARG_ACCESS_WRITE_ONLY 0x11A1 +#define CL_KERNEL_ARG_ACCESS_READ_WRITE 0x11A2 +#define CL_KERNEL_ARG_ACCESS_NONE 0x11A3 + +/* cl_kernel_arg_type_qualifer */ +#define CL_KERNEL_ARG_TYPE_NONE 0 +#define CL_KERNEL_ARG_TYPE_CONST (1 << 0) +#define CL_KERNEL_ARG_TYPE_RESTRICT (1 << 1) +#define CL_KERNEL_ARG_TYPE_VOLATILE (1 << 2) +#define CL_KERNEL_ARG_TYPE_PIPE (1 << 3) + +/* cl_kernel_work_group_info */ +#define CL_KERNEL_WORK_GROUP_SIZE 0x11B0 +#define CL_KERNEL_COMPILE_WORK_GROUP_SIZE 0x11B1 +#define CL_KERNEL_LOCAL_MEM_SIZE 0x11B2 +#define CL_KERNEL_PREFERRED_WORK_GROUP_SIZE_MULTIPLE 0x11B3 +#define CL_KERNEL_PRIVATE_MEM_SIZE 0x11B4 +#define CL_KERNEL_GLOBAL_WORK_SIZE 0x11B5 + +/* cl_kernel_sub_group_info */ +#define CL_KERNEL_MAX_SUB_GROUP_SIZE_FOR_NDRANGE 0x2033 +#define CL_KERNEL_SUB_GROUP_COUNT_FOR_NDRANGE 0x2034 +#define CL_KERNEL_LOCAL_SIZE_FOR_SUB_GROUP_COUNT 0x11B8 + +/* cl_kernel_exec_info */ +#define CL_KERNEL_EXEC_INFO_SVM_PTRS 0x11B6 +#define CL_KERNEL_EXEC_INFO_SVM_FINE_GRAIN_SYSTEM 0x11B7 + +/* cl_event_info */ +#define CL_EVENT_COMMAND_QUEUE 0x11D0 +#define CL_EVENT_COMMAND_TYPE 0x11D1 +#define CL_EVENT_REFERENCE_COUNT 0x11D2 +#define CL_EVENT_COMMAND_EXECUTION_STATUS 0x11D3 +#define CL_EVENT_CONTEXT 0x11D4 + +/* cl_command_type */ +#define CL_COMMAND_NDRANGE_KERNEL 0x11F0 +#define CL_COMMAND_TASK 0x11F1 +#define CL_COMMAND_NATIVE_KERNEL 0x11F2 +#define CL_COMMAND_READ_BUFFER 0x11F3 +#define CL_COMMAND_WRITE_BUFFER 0x11F4 +#define CL_COMMAND_COPY_BUFFER 0x11F5 +#define CL_COMMAND_READ_IMAGE 0x11F6 +#define CL_COMMAND_WRITE_IMAGE 0x11F7 +#define CL_COMMAND_COPY_IMAGE 0x11F8 +#define CL_COMMAND_COPY_IMAGE_TO_BUFFER 0x11F9 +#define CL_COMMAND_COPY_BUFFER_TO_IMAGE 0x11FA +#define CL_COMMAND_MAP_BUFFER 0x11FB +#define CL_COMMAND_MAP_IMAGE 0x11FC +#define CL_COMMAND_UNMAP_MEM_OBJECT 0x11FD +#define CL_COMMAND_MARKER 0x11FE +#define CL_COMMAND_ACQUIRE_GL_OBJECTS 0x11FF +#define CL_COMMAND_RELEASE_GL_OBJECTS 0x1200 +#define CL_COMMAND_READ_BUFFER_RECT 0x1201 +#define CL_COMMAND_WRITE_BUFFER_RECT 0x1202 +#define CL_COMMAND_COPY_BUFFER_RECT 0x1203 +#define CL_COMMAND_USER 0x1204 +#define CL_COMMAND_BARRIER 0x1205 +#define CL_COMMAND_MIGRATE_MEM_OBJECTS 0x1206 +#define CL_COMMAND_FILL_BUFFER 0x1207 +#define CL_COMMAND_FILL_IMAGE 0x1208 +#define CL_COMMAND_SVM_FREE 0x1209 +#define CL_COMMAND_SVM_MEMCPY 0x120A +#define CL_COMMAND_SVM_MEMFILL 0x120B +#define CL_COMMAND_SVM_MAP 0x120C +#define CL_COMMAND_SVM_UNMAP 0x120D + +/* command execution status */ +#define CL_COMPLETE 0x0 +#define CL_RUNNING 0x1 +#define CL_SUBMITTED 0x2 +#define CL_QUEUED 0x3 + +/* cl_buffer_create_type */ +#define CL_BUFFER_CREATE_TYPE_REGION 0x1220 + +/* cl_profiling_info */ +#define CL_PROFILING_COMMAND_QUEUED 0x1280 +#define CL_PROFILING_COMMAND_SUBMIT 0x1281 +#define CL_PROFILING_COMMAND_START 0x1282 +#define CL_PROFILING_COMMAND_END 0x1283 +#define CL_PROFILING_COMMAND_COMPLETE 0x1284 + +/********************************************************************************************************/ + +/* Platform API */ +extern CL_API_ENTRY cl_int CL_API_CALL +clGetPlatformIDs(cl_uint /* num_entries */, + cl_platform_id * /* platforms */, + cl_uint * /* num_platforms */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetPlatformInfo(cl_platform_id /* platform */, + cl_platform_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Device APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceIDs(cl_platform_id /* platform */, + cl_device_type /* device_type */, + cl_uint /* num_entries */, + cl_device_id * /* devices */, + cl_uint * /* num_devices */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceInfo(cl_device_id /* device */, + cl_device_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clCreateSubDevices(cl_device_id /* in_device */, + const cl_device_partition_property * /* properties */, + cl_uint /* num_devices */, + cl_device_id * /* out_devices */, + cl_uint * /* num_devices_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainDevice(cl_device_id /* device */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseDevice(cl_device_id /* device */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetDefaultDeviceCommandQueue(cl_context /* context */, + cl_device_id /* device */, + cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_2_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceAndHostTimer(cl_device_id /* device */, + cl_ulong* /* device_timestamp */, + cl_ulong* /* host_timestamp */) CL_API_SUFFIX__VERSION_2_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetHostTimer(cl_device_id /* device */, + cl_ulong * /* host_timestamp */) CL_API_SUFFIX__VERSION_2_1; + + +/* Context APIs */ +extern CL_API_ENTRY cl_context CL_API_CALL +clCreateContext(const cl_context_properties * /* properties */, + cl_uint /* num_devices */, + const cl_device_id * /* devices */, + void (CL_CALLBACK * /* pfn_notify */)(const char *, const void *, size_t, void *), + void * /* user_data */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_context CL_API_CALL +clCreateContextFromType(const cl_context_properties * /* properties */, + cl_device_type /* device_type */, + void (CL_CALLBACK * /* pfn_notify*/ )(const char *, const void *, size_t, void *), + void * /* user_data */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainContext(cl_context /* context */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseContext(cl_context /* context */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetContextInfo(cl_context /* context */, + cl_context_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Command Queue APIs */ +extern CL_API_ENTRY cl_command_queue CL_API_CALL +clCreateCommandQueueWithProperties(cl_context /* context */, + cl_device_id /* device */, + const cl_queue_properties * /* properties */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainCommandQueue(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseCommandQueue(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetCommandQueueInfo(cl_command_queue /* command_queue */, + cl_command_queue_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Memory Object APIs */ +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateBuffer(cl_context /* context */, + cl_mem_flags /* flags */, + size_t /* size */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateSubBuffer(cl_mem /* buffer */, + cl_mem_flags /* flags */, + cl_buffer_create_type /* buffer_create_type */, + const void * /* buffer_create_info */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateImage(cl_context /* context */, + cl_mem_flags /* flags */, + const cl_image_format * /* image_format */, + const cl_image_desc * /* image_desc */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreatePipe(cl_context /* context */, + cl_mem_flags /* flags */, + cl_uint /* pipe_packet_size */, + cl_uint /* pipe_max_packets */, + const cl_pipe_properties * /* properties */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainMemObject(cl_mem /* memobj */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseMemObject(cl_mem /* memobj */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetSupportedImageFormats(cl_context /* context */, + cl_mem_flags /* flags */, + cl_mem_object_type /* image_type */, + cl_uint /* num_entries */, + cl_image_format * /* image_formats */, + cl_uint * /* num_image_formats */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetMemObjectInfo(cl_mem /* memobj */, + cl_mem_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetImageInfo(cl_mem /* image */, + cl_image_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetPipeInfo(cl_mem /* pipe */, + cl_pipe_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_2_0; + + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetMemObjectDestructorCallback(cl_mem /* memobj */, + void (CL_CALLBACK * /*pfn_notify*/)( cl_mem /* memobj */, void* /*user_data*/), + void * /*user_data */ ) CL_API_SUFFIX__VERSION_1_1; + +/* SVM Allocation APIs */ +extern CL_API_ENTRY void * CL_API_CALL +clSVMAlloc(cl_context /* context */, + cl_svm_mem_flags /* flags */, + size_t /* size */, + cl_uint /* alignment */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY void CL_API_CALL +clSVMFree(cl_context /* context */, + void * /* svm_pointer */) CL_API_SUFFIX__VERSION_2_0; + +/* Sampler APIs */ +extern CL_API_ENTRY cl_sampler CL_API_CALL +clCreateSamplerWithProperties(cl_context /* context */, + const cl_sampler_properties * /* normalized_coords */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainSampler(cl_sampler /* sampler */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseSampler(cl_sampler /* sampler */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetSamplerInfo(cl_sampler /* sampler */, + cl_sampler_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Program Object APIs */ +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithSource(cl_context /* context */, + cl_uint /* count */, + const char ** /* strings */, + const size_t * /* lengths */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithBinary(cl_context /* context */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const size_t * /* lengths */, + const unsigned char ** /* binaries */, + cl_int * /* binary_status */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithBuiltInKernels(cl_context /* context */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* kernel_names */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithIL(cl_context /* context */, + const void* /* il */, + size_t /* length */, + cl_int* /* errcode_ret */) CL_API_SUFFIX__VERSION_2_1; + + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainProgram(cl_program /* program */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseProgram(cl_program /* program */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clBuildProgram(cl_program /* program */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* options */, + void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), + void * /* user_data */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clCompileProgram(cl_program /* program */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* options */, + cl_uint /* num_input_headers */, + const cl_program * /* input_headers */, + const char ** /* header_include_names */, + void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), + void * /* user_data */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_program CL_API_CALL +clLinkProgram(cl_context /* context */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* options */, + cl_uint /* num_input_programs */, + const cl_program * /* input_programs */, + void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), + void * /* user_data */, + cl_int * /* errcode_ret */ ) CL_API_SUFFIX__VERSION_1_2; + + +extern CL_API_ENTRY cl_int CL_API_CALL +clUnloadPlatformCompiler(cl_platform_id /* platform */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetProgramInfo(cl_program /* program */, + cl_program_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetProgramBuildInfo(cl_program /* program */, + cl_device_id /* device */, + cl_program_build_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Kernel Object APIs */ +extern CL_API_ENTRY cl_kernel CL_API_CALL +clCreateKernel(cl_program /* program */, + const char * /* kernel_name */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clCreateKernelsInProgram(cl_program /* program */, + cl_uint /* num_kernels */, + cl_kernel * /* kernels */, + cl_uint * /* num_kernels_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_kernel CL_API_CALL +clCloneKernel(cl_kernel /* source_kernel */, + cl_int* /* errcode_ret */) CL_API_SUFFIX__VERSION_2_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainKernel(cl_kernel /* kernel */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseKernel(cl_kernel /* kernel */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetKernelArg(cl_kernel /* kernel */, + cl_uint /* arg_index */, + size_t /* arg_size */, + const void * /* arg_value */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetKernelArgSVMPointer(cl_kernel /* kernel */, + cl_uint /* arg_index */, + const void * /* arg_value */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetKernelExecInfo(cl_kernel /* kernel */, + cl_kernel_exec_info /* param_name */, + size_t /* param_value_size */, + const void * /* param_value */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelInfo(cl_kernel /* kernel */, + cl_kernel_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelArgInfo(cl_kernel /* kernel */, + cl_uint /* arg_indx */, + cl_kernel_arg_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelWorkGroupInfo(cl_kernel /* kernel */, + cl_device_id /* device */, + cl_kernel_work_group_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelSubGroupInfo(cl_kernel /* kernel */, + cl_device_id /* device */, + cl_kernel_sub_group_info /* param_name */, + size_t /* input_value_size */, + const void* /*input_value */, + size_t /* param_value_size */, + void* /* param_value */, + size_t* /* param_value_size_ret */ ) CL_API_SUFFIX__VERSION_2_1; + + +/* Event Object APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clWaitForEvents(cl_uint /* num_events */, + const cl_event * /* event_list */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetEventInfo(cl_event /* event */, + cl_event_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_event CL_API_CALL +clCreateUserEvent(cl_context /* context */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainEvent(cl_event /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseEvent(cl_event /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetUserEventStatus(cl_event /* event */, + cl_int /* execution_status */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetEventCallback( cl_event /* event */, + cl_int /* command_exec_callback_type */, + void (CL_CALLBACK * /* pfn_notify */)(cl_event, cl_int, void *), + void * /* user_data */) CL_API_SUFFIX__VERSION_1_1; + +/* Profiling APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clGetEventProfilingInfo(cl_event /* event */, + cl_profiling_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Flush and Finish APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clFlush(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clFinish(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +/* Enqueued Commands APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReadBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_read */, + size_t /* offset */, + size_t /* size */, + void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReadBufferRect(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_read */, + const size_t * /* buffer_offset */, + const size_t * /* host_offset */, + const size_t * /* region */, + size_t /* buffer_row_pitch */, + size_t /* buffer_slice_pitch */, + size_t /* host_row_pitch */, + size_t /* host_slice_pitch */, + void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueWriteBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_write */, + size_t /* offset */, + size_t /* size */, + const void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueWriteBufferRect(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_write */, + const size_t * /* buffer_offset */, + const size_t * /* host_offset */, + const size_t * /* region */, + size_t /* buffer_row_pitch */, + size_t /* buffer_slice_pitch */, + size_t /* host_row_pitch */, + size_t /* host_slice_pitch */, + const void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueFillBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + const void * /* pattern */, + size_t /* pattern_size */, + size_t /* offset */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyBuffer(cl_command_queue /* command_queue */, + cl_mem /* src_buffer */, + cl_mem /* dst_buffer */, + size_t /* src_offset */, + size_t /* dst_offset */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyBufferRect(cl_command_queue /* command_queue */, + cl_mem /* src_buffer */, + cl_mem /* dst_buffer */, + const size_t * /* src_origin */, + const size_t * /* dst_origin */, + const size_t * /* region */, + size_t /* src_row_pitch */, + size_t /* src_slice_pitch */, + size_t /* dst_row_pitch */, + size_t /* dst_slice_pitch */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReadImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + cl_bool /* blocking_read */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + size_t /* row_pitch */, + size_t /* slice_pitch */, + void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueWriteImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + cl_bool /* blocking_write */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + size_t /* input_row_pitch */, + size_t /* input_slice_pitch */, + const void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueFillImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + const void * /* fill_color */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyImage(cl_command_queue /* command_queue */, + cl_mem /* src_image */, + cl_mem /* dst_image */, + const size_t * /* src_origin[3] */, + const size_t * /* dst_origin[3] */, + const size_t * /* region[3] */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyImageToBuffer(cl_command_queue /* command_queue */, + cl_mem /* src_image */, + cl_mem /* dst_buffer */, + const size_t * /* src_origin[3] */, + const size_t * /* region[3] */, + size_t /* dst_offset */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyBufferToImage(cl_command_queue /* command_queue */, + cl_mem /* src_buffer */, + cl_mem /* dst_image */, + size_t /* src_offset */, + const size_t * /* dst_origin[3] */, + const size_t * /* region[3] */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY void * CL_API_CALL +clEnqueueMapBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_map */, + cl_map_flags /* map_flags */, + size_t /* offset */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY void * CL_API_CALL +clEnqueueMapImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + cl_bool /* blocking_map */, + cl_map_flags /* map_flags */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + size_t * /* image_row_pitch */, + size_t * /* image_slice_pitch */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueUnmapMemObject(cl_command_queue /* command_queue */, + cl_mem /* memobj */, + void * /* mapped_ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueMigrateMemObjects(cl_command_queue /* command_queue */, + cl_uint /* num_mem_objects */, + const cl_mem * /* mem_objects */, + cl_mem_migration_flags /* flags */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueNDRangeKernel(cl_command_queue /* command_queue */, + cl_kernel /* kernel */, + cl_uint /* work_dim */, + const size_t * /* global_work_offset */, + const size_t * /* global_work_size */, + const size_t * /* local_work_size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueNativeKernel(cl_command_queue /* command_queue */, + void (CL_CALLBACK * /*user_func*/)(void *), + void * /* args */, + size_t /* cb_args */, + cl_uint /* num_mem_objects */, + const cl_mem * /* mem_list */, + const void ** /* args_mem_loc */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueMarkerWithWaitList(cl_command_queue /* command_queue */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueBarrierWithWaitList(cl_command_queue /* command_queue */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMFree(cl_command_queue /* command_queue */, + cl_uint /* num_svm_pointers */, + void *[] /* svm_pointers[] */, + void (CL_CALLBACK * /*pfn_free_func*/)(cl_command_queue /* queue */, + cl_uint /* num_svm_pointers */, + void *[] /* svm_pointers[] */, + void * /* user_data */), + void * /* user_data */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMemcpy(cl_command_queue /* command_queue */, + cl_bool /* blocking_copy */, + void * /* dst_ptr */, + const void * /* src_ptr */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMemFill(cl_command_queue /* command_queue */, + void * /* svm_ptr */, + const void * /* pattern */, + size_t /* pattern_size */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMap(cl_command_queue /* command_queue */, + cl_bool /* blocking_map */, + cl_map_flags /* flags */, + void * /* svm_ptr */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMUnmap(cl_command_queue /* command_queue */, + void * /* svm_ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMigrateMem(cl_command_queue /* command_queue */, + cl_uint /* num_svm_pointers */, + const void ** /* svm_pointers */, + const size_t * /* sizes */, + cl_mem_migration_flags /* flags */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_1; + + +/* Extension function access + * + * Returns the extension function address for the given function name, + * or NULL if a valid function can not be found. The client must + * check to make sure the address is not NULL, before using or + * calling the returned function address. + */ +extern CL_API_ENTRY void * CL_API_CALL +clGetExtensionFunctionAddressForPlatform(cl_platform_id /* platform */, + const char * /* func_name */) CL_API_SUFFIX__VERSION_1_2; + + +/* Deprecated OpenCL 1.1 APIs */ +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateImage2D(cl_context /* context */, + cl_mem_flags /* flags */, + const cl_image_format * /* image_format */, + size_t /* image_width */, + size_t /* image_height */, + size_t /* image_row_pitch */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateImage3D(cl_context /* context */, + cl_mem_flags /* flags */, + const cl_image_format * /* image_format */, + size_t /* image_width */, + size_t /* image_height */, + size_t /* image_depth */, + size_t /* image_row_pitch */, + size_t /* image_slice_pitch */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clEnqueueMarker(cl_command_queue /* command_queue */, + cl_event * /* event */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clEnqueueWaitForEvents(cl_command_queue /* command_queue */, + cl_uint /* num_events */, + const cl_event * /* event_list */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clEnqueueBarrier(cl_command_queue /* command_queue */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clUnloadCompiler(void) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED void * CL_API_CALL +clGetExtensionFunctionAddress(const char * /* func_name */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +/* Deprecated OpenCL 2.0 APIs */ +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_command_queue CL_API_CALL +clCreateCommandQueue(cl_context /* context */, + cl_device_id /* device */, + cl_command_queue_properties /* properties */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; + + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_sampler CL_API_CALL +clCreateSampler(cl_context /* context */, + cl_bool /* normalized_coords */, + cl_addressing_mode /* addressing_mode */, + cl_filter_mode /* filter_mode */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_int CL_API_CALL +clEnqueueTask(cl_command_queue /* command_queue */, + cl_kernel /* kernel */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_H */ + diff --git a/phonelibs/opencl/include/CL/cl_d3d10.h b/phonelibs/opencl/include/CL/cl_d3d10.h new file mode 100644 index 00000000000000..d5960a43f72123 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_d3d10.h @@ -0,0 +1,131 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_CL_D3D10_H +#define __OPENCL_CL_D3D10_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/****************************************************************************** + * cl_khr_d3d10_sharing */ +#define cl_khr_d3d10_sharing 1 + +typedef cl_uint cl_d3d10_device_source_khr; +typedef cl_uint cl_d3d10_device_set_khr; + +/******************************************************************************/ + +/* Error Codes */ +#define CL_INVALID_D3D10_DEVICE_KHR -1002 +#define CL_INVALID_D3D10_RESOURCE_KHR -1003 +#define CL_D3D10_RESOURCE_ALREADY_ACQUIRED_KHR -1004 +#define CL_D3D10_RESOURCE_NOT_ACQUIRED_KHR -1005 + +/* cl_d3d10_device_source_nv */ +#define CL_D3D10_DEVICE_KHR 0x4010 +#define CL_D3D10_DXGI_ADAPTER_KHR 0x4011 + +/* cl_d3d10_device_set_nv */ +#define CL_PREFERRED_DEVICES_FOR_D3D10_KHR 0x4012 +#define CL_ALL_DEVICES_FOR_D3D10_KHR 0x4013 + +/* cl_context_info */ +#define CL_CONTEXT_D3D10_DEVICE_KHR 0x4014 +#define CL_CONTEXT_D3D10_PREFER_SHARED_RESOURCES_KHR 0x402C + +/* cl_mem_info */ +#define CL_MEM_D3D10_RESOURCE_KHR 0x4015 + +/* cl_image_info */ +#define CL_IMAGE_D3D10_SUBRESOURCE_KHR 0x4016 + +/* cl_command_type */ +#define CL_COMMAND_ACQUIRE_D3D10_OBJECTS_KHR 0x4017 +#define CL_COMMAND_RELEASE_D3D10_OBJECTS_KHR 0x4018 + +/******************************************************************************/ + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromD3D10KHR_fn)( + cl_platform_id platform, + cl_d3d10_device_source_khr d3d_device_source, + void * d3d_object, + cl_d3d10_device_set_khr d3d_device_set, + cl_uint num_entries, + cl_device_id * devices, + cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10BufferKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D10Buffer * resource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10Texture2DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D10Texture2D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10Texture3DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D10Texture3D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireD3D10ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseD3D10ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_0; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_D3D10_H */ + diff --git a/phonelibs/opencl/include/CL/cl_d3d11.h b/phonelibs/opencl/include/CL/cl_d3d11.h new file mode 100644 index 00000000000000..39f9072398a29a --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_d3d11.h @@ -0,0 +1,131 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_CL_D3D11_H +#define __OPENCL_CL_D3D11_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/****************************************************************************** + * cl_khr_d3d11_sharing */ +#define cl_khr_d3d11_sharing 1 + +typedef cl_uint cl_d3d11_device_source_khr; +typedef cl_uint cl_d3d11_device_set_khr; + +/******************************************************************************/ + +/* Error Codes */ +#define CL_INVALID_D3D11_DEVICE_KHR -1006 +#define CL_INVALID_D3D11_RESOURCE_KHR -1007 +#define CL_D3D11_RESOURCE_ALREADY_ACQUIRED_KHR -1008 +#define CL_D3D11_RESOURCE_NOT_ACQUIRED_KHR -1009 + +/* cl_d3d11_device_source */ +#define CL_D3D11_DEVICE_KHR 0x4019 +#define CL_D3D11_DXGI_ADAPTER_KHR 0x401A + +/* cl_d3d11_device_set */ +#define CL_PREFERRED_DEVICES_FOR_D3D11_KHR 0x401B +#define CL_ALL_DEVICES_FOR_D3D11_KHR 0x401C + +/* cl_context_info */ +#define CL_CONTEXT_D3D11_DEVICE_KHR 0x401D +#define CL_CONTEXT_D3D11_PREFER_SHARED_RESOURCES_KHR 0x402D + +/* cl_mem_info */ +#define CL_MEM_D3D11_RESOURCE_KHR 0x401E + +/* cl_image_info */ +#define CL_IMAGE_D3D11_SUBRESOURCE_KHR 0x401F + +/* cl_command_type */ +#define CL_COMMAND_ACQUIRE_D3D11_OBJECTS_KHR 0x4020 +#define CL_COMMAND_RELEASE_D3D11_OBJECTS_KHR 0x4021 + +/******************************************************************************/ + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromD3D11KHR_fn)( + cl_platform_id platform, + cl_d3d11_device_source_khr d3d_device_source, + void * d3d_object, + cl_d3d11_device_set_khr d3d_device_set, + cl_uint num_entries, + cl_device_id * devices, + cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11BufferKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D11Buffer * resource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11Texture2DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D11Texture2D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11Texture3DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D11Texture3D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireD3D11ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseD3D11ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_D3D11_H */ + diff --git a/phonelibs/opencl/include/CL/cl_dx9_media_sharing.h b/phonelibs/opencl/include/CL/cl_dx9_media_sharing.h new file mode 100644 index 00000000000000..2729e8b9e89a10 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_dx9_media_sharing.h @@ -0,0 +1,132 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_CL_DX9_MEDIA_SHARING_H +#define __OPENCL_CL_DX9_MEDIA_SHARING_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/******************************************************************************/ +/* cl_khr_dx9_media_sharing */ +#define cl_khr_dx9_media_sharing 1 + +typedef cl_uint cl_dx9_media_adapter_type_khr; +typedef cl_uint cl_dx9_media_adapter_set_khr; + +#if defined(_WIN32) +#include +typedef struct _cl_dx9_surface_info_khr +{ + IDirect3DSurface9 *resource; + HANDLE shared_handle; +} cl_dx9_surface_info_khr; +#endif + + +/******************************************************************************/ + +/* Error Codes */ +#define CL_INVALID_DX9_MEDIA_ADAPTER_KHR -1010 +#define CL_INVALID_DX9_MEDIA_SURFACE_KHR -1011 +#define CL_DX9_MEDIA_SURFACE_ALREADY_ACQUIRED_KHR -1012 +#define CL_DX9_MEDIA_SURFACE_NOT_ACQUIRED_KHR -1013 + +/* cl_media_adapter_type_khr */ +#define CL_ADAPTER_D3D9_KHR 0x2020 +#define CL_ADAPTER_D3D9EX_KHR 0x2021 +#define CL_ADAPTER_DXVA_KHR 0x2022 + +/* cl_media_adapter_set_khr */ +#define CL_PREFERRED_DEVICES_FOR_DX9_MEDIA_ADAPTER_KHR 0x2023 +#define CL_ALL_DEVICES_FOR_DX9_MEDIA_ADAPTER_KHR 0x2024 + +/* cl_context_info */ +#define CL_CONTEXT_ADAPTER_D3D9_KHR 0x2025 +#define CL_CONTEXT_ADAPTER_D3D9EX_KHR 0x2026 +#define CL_CONTEXT_ADAPTER_DXVA_KHR 0x2027 + +/* cl_mem_info */ +#define CL_MEM_DX9_MEDIA_ADAPTER_TYPE_KHR 0x2028 +#define CL_MEM_DX9_MEDIA_SURFACE_INFO_KHR 0x2029 + +/* cl_image_info */ +#define CL_IMAGE_DX9_MEDIA_PLANE_KHR 0x202A + +/* cl_command_type */ +#define CL_COMMAND_ACQUIRE_DX9_MEDIA_SURFACES_KHR 0x202B +#define CL_COMMAND_RELEASE_DX9_MEDIA_SURFACES_KHR 0x202C + +/******************************************************************************/ + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromDX9MediaAdapterKHR_fn)( + cl_platform_id platform, + cl_uint num_media_adapters, + cl_dx9_media_adapter_type_khr * media_adapter_type, + void * media_adapters, + cl_dx9_media_adapter_set_khr media_adapter_set, + cl_uint num_entries, + cl_device_id * devices, + cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromDX9MediaSurfaceKHR_fn)( + cl_context context, + cl_mem_flags flags, + cl_dx9_media_adapter_type_khr adapter_type, + void * surface_info, + cl_uint plane, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireDX9MediaSurfacesKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseDX9MediaSurfacesKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_DX9_MEDIA_SHARING_H */ + diff --git a/phonelibs/opencl/include/CL/cl_egl.h b/phonelibs/opencl/include/CL/cl_egl.h new file mode 100644 index 00000000000000..a765bd5266c02f --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_egl.h @@ -0,0 +1,136 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +#ifndef __OPENCL_CL_EGL_H +#define __OPENCL_CL_EGL_H + +#ifdef __APPLE__ + +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Command type for events created with clEnqueueAcquireEGLObjectsKHR */ +#define CL_COMMAND_EGL_FENCE_SYNC_OBJECT_KHR 0x202F +#define CL_COMMAND_ACQUIRE_EGL_OBJECTS_KHR 0x202D +#define CL_COMMAND_RELEASE_EGL_OBJECTS_KHR 0x202E + +/* Error type for clCreateFromEGLImageKHR */ +#define CL_INVALID_EGL_OBJECT_KHR -1093 +#define CL_EGL_RESOURCE_NOT_ACQUIRED_KHR -1092 + +/* CLeglImageKHR is an opaque handle to an EGLImage */ +typedef void* CLeglImageKHR; + +/* CLeglDisplayKHR is an opaque handle to an EGLDisplay */ +typedef void* CLeglDisplayKHR; + +/* CLeglSyncKHR is an opaque handle to an EGLSync object */ +typedef void* CLeglSyncKHR; + +/* properties passed to clCreateFromEGLImageKHR */ +typedef intptr_t cl_egl_image_properties_khr; + + +#define cl_khr_egl_image 1 + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromEGLImageKHR(cl_context /* context */, + CLeglDisplayKHR /* egldisplay */, + CLeglImageKHR /* eglimage */, + cl_mem_flags /* flags */, + const cl_egl_image_properties_khr * /* properties */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromEGLImageKHR_fn)( + cl_context context, + CLeglDisplayKHR egldisplay, + CLeglImageKHR eglimage, + cl_mem_flags flags, + const cl_egl_image_properties_khr * properties, + cl_int * errcode_ret); + + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueAcquireEGLObjectsKHR(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireEGLObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event); + + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReleaseEGLObjectsKHR(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseEGLObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event); + + +#define cl_khr_egl_event 1 + +extern CL_API_ENTRY cl_event CL_API_CALL +clCreateEventFromEGLSyncKHR(cl_context /* context */, + CLeglSyncKHR /* sync */, + CLeglDisplayKHR /* display */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_event (CL_API_CALL *clCreateEventFromEGLSyncKHR_fn)( + cl_context context, + CLeglSyncKHR sync, + CLeglDisplayKHR display, + cl_int * errcode_ret); + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_EGL_H */ diff --git a/phonelibs/opencl/include/CL/cl_ext.h b/phonelibs/opencl/include/CL/cl_ext.h new file mode 100644 index 00000000000000..7941583895c57b --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_ext.h @@ -0,0 +1,391 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +/* $Revision: 11928 $ on $Date: 2010-07-13 09:04:56 -0700 (Tue, 13 Jul 2010) $ */ + +/* cl_ext.h contains OpenCL extensions which don't have external */ +/* (OpenGL, D3D) dependencies. */ + +#ifndef __CL_EXT_H +#define __CL_EXT_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef __APPLE__ + #include + #include +#else + #include +#endif + +/* cl_khr_fp16 extension - no extension #define since it has no functions */ +#define CL_DEVICE_HALF_FP_CONFIG 0x1033 + +/* Memory object destruction + * + * Apple extension for use to manage externally allocated buffers used with cl_mem objects with CL_MEM_USE_HOST_PTR + * + * Registers a user callback function that will be called when the memory object is deleted and its resources + * freed. Each call to clSetMemObjectCallbackFn registers the specified user callback function on a callback + * stack associated with memobj. The registered user callback functions are called in the reverse order in + * which they were registered. The user callback functions are called and then the memory object is deleted + * and its resources freed. This provides a mechanism for the application (and libraries) using memobj to be + * notified when the memory referenced by host_ptr, specified when the memory object is created and used as + * the storage bits for the memory object, can be reused or freed. + * + * The application may not call CL api's with the cl_mem object passed to the pfn_notify. + * + * Please check for the "cl_APPLE_SetMemObjectDestructor" extension using clGetDeviceInfo(CL_DEVICE_EXTENSIONS) + * before using. + */ +#define cl_APPLE_SetMemObjectDestructor 1 +cl_int CL_API_ENTRY clSetMemObjectDestructorAPPLE( cl_mem /* memobj */, + void (* /*pfn_notify*/)( cl_mem /* memobj */, void* /*user_data*/), + void * /*user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + + +/* Context Logging Functions + * + * The next three convenience functions are intended to be used as the pfn_notify parameter to clCreateContext(). + * Please check for the "cl_APPLE_ContextLoggingFunctions" extension using clGetDeviceInfo(CL_DEVICE_EXTENSIONS) + * before using. + * + * clLogMessagesToSystemLog fowards on all log messages to the Apple System Logger + */ +#define cl_APPLE_ContextLoggingFunctions 1 +extern void CL_API_ENTRY clLogMessagesToSystemLogAPPLE( const char * /* errstr */, + const void * /* private_info */, + size_t /* cb */, + void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + +/* clLogMessagesToStdout sends all log messages to the file descriptor stdout */ +extern void CL_API_ENTRY clLogMessagesToStdoutAPPLE( const char * /* errstr */, + const void * /* private_info */, + size_t /* cb */, + void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + +/* clLogMessagesToStderr sends all log messages to the file descriptor stderr */ +extern void CL_API_ENTRY clLogMessagesToStderrAPPLE( const char * /* errstr */, + const void * /* private_info */, + size_t /* cb */, + void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + + +/************************ +* cl_khr_icd extension * +************************/ +#define cl_khr_icd 1 + +/* cl_platform_info */ +#define CL_PLATFORM_ICD_SUFFIX_KHR 0x0920 + +/* Additional Error Codes */ +#define CL_PLATFORM_NOT_FOUND_KHR -1001 + +extern CL_API_ENTRY cl_int CL_API_CALL +clIcdGetPlatformIDsKHR(cl_uint /* num_entries */, + cl_platform_id * /* platforms */, + cl_uint * /* num_platforms */); + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clIcdGetPlatformIDsKHR_fn)( + cl_uint /* num_entries */, + cl_platform_id * /* platforms */, + cl_uint * /* num_platforms */); + + +/* Extension: cl_khr_image2D_buffer + * + * This extension allows a 2D image to be created from a cl_mem buffer without a copy. + * The type associated with a 2D image created from a buffer in an OpenCL program is image2d_t. + * Both the sampler and sampler-less read_image built-in functions are supported for 2D images + * and 2D images created from a buffer. Similarly, the write_image built-ins are also supported + * for 2D images created from a buffer. + * + * When the 2D image from buffer is created, the client must specify the width, + * height, image format (i.e. channel order and channel data type) and optionally the row pitch + * + * The pitch specified must be a multiple of CL_DEVICE_IMAGE_PITCH_ALIGNMENT pixels. + * The base address of the buffer must be aligned to CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT pixels. + */ + +/************************************* + * cl_khr_initalize_memory extension * + *************************************/ + +#define CL_CONTEXT_MEMORY_INITIALIZE_KHR 0x2030 + + +/************************************** + * cl_khr_terminate_context extension * + **************************************/ + +#define CL_DEVICE_TERMINATE_CAPABILITY_KHR 0x2031 +#define CL_CONTEXT_TERMINATE_KHR 0x2032 + +#define cl_khr_terminate_context 1 +extern CL_API_ENTRY cl_int CL_API_CALL clTerminateContextKHR(cl_context /* context */) CL_EXT_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clTerminateContextKHR_fn)(cl_context /* context */) CL_EXT_SUFFIX__VERSION_1_2; + + +/* + * Extension: cl_khr_spir + * + * This extension adds support to create an OpenCL program object from a + * Standard Portable Intermediate Representation (SPIR) instance + */ + +#define CL_DEVICE_SPIR_VERSIONS 0x40E0 +#define CL_PROGRAM_BINARY_TYPE_INTERMEDIATE 0x40E1 + + +/****************************************** +* cl_nv_device_attribute_query extension * +******************************************/ +/* cl_nv_device_attribute_query extension - no extension #define since it has no functions */ +#define CL_DEVICE_COMPUTE_CAPABILITY_MAJOR_NV 0x4000 +#define CL_DEVICE_COMPUTE_CAPABILITY_MINOR_NV 0x4001 +#define CL_DEVICE_REGISTERS_PER_BLOCK_NV 0x4002 +#define CL_DEVICE_WARP_SIZE_NV 0x4003 +#define CL_DEVICE_GPU_OVERLAP_NV 0x4004 +#define CL_DEVICE_KERNEL_EXEC_TIMEOUT_NV 0x4005 +#define CL_DEVICE_INTEGRATED_MEMORY_NV 0x4006 + +/********************************* +* cl_amd_device_attribute_query * +*********************************/ +#define CL_DEVICE_PROFILING_TIMER_OFFSET_AMD 0x4036 + +/********************************* +* cl_arm_printf extension +*********************************/ +#define CL_PRINTF_CALLBACK_ARM 0x40B0 +#define CL_PRINTF_BUFFERSIZE_ARM 0x40B1 + +#ifdef CL_VERSION_1_1 + /*********************************** + * cl_ext_device_fission extension * + ***********************************/ + #define cl_ext_device_fission 1 + + extern CL_API_ENTRY cl_int CL_API_CALL + clReleaseDeviceEXT( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef CL_API_ENTRY cl_int + (CL_API_CALL *clReleaseDeviceEXT_fn)( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + extern CL_API_ENTRY cl_int CL_API_CALL + clRetainDeviceEXT( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef CL_API_ENTRY cl_int + (CL_API_CALL *clRetainDeviceEXT_fn)( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef cl_ulong cl_device_partition_property_ext; + extern CL_API_ENTRY cl_int CL_API_CALL + clCreateSubDevicesEXT( cl_device_id /*in_device*/, + const cl_device_partition_property_ext * /* properties */, + cl_uint /*num_entries*/, + cl_device_id * /*out_devices*/, + cl_uint * /*num_devices*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef CL_API_ENTRY cl_int + ( CL_API_CALL * clCreateSubDevicesEXT_fn)( cl_device_id /*in_device*/, + const cl_device_partition_property_ext * /* properties */, + cl_uint /*num_entries*/, + cl_device_id * /*out_devices*/, + cl_uint * /*num_devices*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + /* cl_device_partition_property_ext */ + #define CL_DEVICE_PARTITION_EQUALLY_EXT 0x4050 + #define CL_DEVICE_PARTITION_BY_COUNTS_EXT 0x4051 + #define CL_DEVICE_PARTITION_BY_NAMES_EXT 0x4052 + #define CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN_EXT 0x4053 + + /* clDeviceGetInfo selectors */ + #define CL_DEVICE_PARENT_DEVICE_EXT 0x4054 + #define CL_DEVICE_PARTITION_TYPES_EXT 0x4055 + #define CL_DEVICE_AFFINITY_DOMAINS_EXT 0x4056 + #define CL_DEVICE_REFERENCE_COUNT_EXT 0x4057 + #define CL_DEVICE_PARTITION_STYLE_EXT 0x4058 + + /* error codes */ + #define CL_DEVICE_PARTITION_FAILED_EXT -1057 + #define CL_INVALID_PARTITION_COUNT_EXT -1058 + #define CL_INVALID_PARTITION_NAME_EXT -1059 + + /* CL_AFFINITY_DOMAINs */ + #define CL_AFFINITY_DOMAIN_L1_CACHE_EXT 0x1 + #define CL_AFFINITY_DOMAIN_L2_CACHE_EXT 0x2 + #define CL_AFFINITY_DOMAIN_L3_CACHE_EXT 0x3 + #define CL_AFFINITY_DOMAIN_L4_CACHE_EXT 0x4 + #define CL_AFFINITY_DOMAIN_NUMA_EXT 0x10 + #define CL_AFFINITY_DOMAIN_NEXT_FISSIONABLE_EXT 0x100 + + /* cl_device_partition_property_ext list terminators */ + #define CL_PROPERTIES_LIST_END_EXT ((cl_device_partition_property_ext) 0) + #define CL_PARTITION_BY_COUNTS_LIST_END_EXT ((cl_device_partition_property_ext) 0) + #define CL_PARTITION_BY_NAMES_LIST_END_EXT ((cl_device_partition_property_ext) 0 - 1) + +/********************************* +* cl_qcom_ext_host_ptr extension +*********************************/ + +#define CL_MEM_EXT_HOST_PTR_QCOM (1 << 29) + +#define CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM 0x40A0 +#define CL_DEVICE_PAGE_SIZE_QCOM 0x40A1 +#define CL_IMAGE_ROW_ALIGNMENT_QCOM 0x40A2 +#define CL_IMAGE_SLICE_ALIGNMENT_QCOM 0x40A3 +#define CL_MEM_HOST_UNCACHED_QCOM 0x40A4 +#define CL_MEM_HOST_WRITEBACK_QCOM 0x40A5 +#define CL_MEM_HOST_WRITETHROUGH_QCOM 0x40A6 +#define CL_MEM_HOST_WRITE_COMBINING_QCOM 0x40A7 + +typedef cl_uint cl_image_pitch_info_qcom; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceImageInfoQCOM(cl_device_id device, + size_t image_width, + size_t image_height, + const cl_image_format *image_format, + cl_image_pitch_info_qcom param_name, + size_t param_value_size, + void *param_value, + size_t *param_value_size_ret); + +typedef struct _cl_mem_ext_host_ptr +{ + /* Type of external memory allocation. */ + /* Legal values will be defined in layered extensions. */ + cl_uint allocation_type; + + /* Host cache policy for this external memory allocation. */ + cl_uint host_cache_policy; + +} cl_mem_ext_host_ptr; + +/********************************* +* cl_qcom_ion_host_ptr extension +*********************************/ + +#define CL_MEM_ION_HOST_PTR_QCOM 0x40A8 + +typedef struct _cl_mem_ion_host_ptr +{ + /* Type of external memory allocation. */ + /* Must be CL_MEM_ION_HOST_PTR_QCOM for ION allocations. */ + cl_mem_ext_host_ptr ext_host_ptr; + + /* ION file descriptor */ + int ion_filedesc; + + /* Host pointer to the ION allocated memory */ + void* ion_hostptr; + +} cl_mem_ion_host_ptr; + +#endif /* CL_VERSION_1_1 */ + + +#ifdef CL_VERSION_2_0 +/********************************* +* cl_khr_sub_groups extension +*********************************/ +#define cl_khr_sub_groups 1 + +typedef cl_uint cl_kernel_sub_group_info_khr; + +/* cl_khr_sub_group_info */ +#define CL_KERNEL_MAX_SUB_GROUP_SIZE_FOR_NDRANGE_KHR 0x2033 +#define CL_KERNEL_SUB_GROUP_COUNT_FOR_NDRANGE_KHR 0x2034 + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelSubGroupInfoKHR(cl_kernel /* in_kernel */, + cl_device_id /*in_device*/, + cl_kernel_sub_group_info_khr /* param_name */, + size_t /*input_value_size*/, + const void * /*input_value*/, + size_t /*param_value_size*/, + void* /*param_value*/, + size_t* /*param_value_size_ret*/ ) CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED; + +typedef CL_API_ENTRY cl_int + ( CL_API_CALL * clGetKernelSubGroupInfoKHR_fn)(cl_kernel /* in_kernel */, + cl_device_id /*in_device*/, + cl_kernel_sub_group_info_khr /* param_name */, + size_t /*input_value_size*/, + const void * /*input_value*/, + size_t /*param_value_size*/, + void* /*param_value*/, + size_t* /*param_value_size_ret*/ ) CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED; +#endif /* CL_VERSION_2_0 */ + +#ifdef CL_VERSION_2_1 +/********************************* +* cl_khr_priority_hints extension +*********************************/ +#define cl_khr_priority_hints 1 + +typedef cl_uint cl_queue_priority_khr; + +/* cl_command_queue_properties */ +#define CL_QUEUE_PRIORITY_KHR 0x1096 + +/* cl_queue_priority_khr */ +#define CL_QUEUE_PRIORITY_HIGH_KHR (1<<0) +#define CL_QUEUE_PRIORITY_MED_KHR (1<<1) +#define CL_QUEUE_PRIORITY_LOW_KHR (1<<2) + +#endif /* CL_VERSION_2_1 */ + +#ifdef CL_VERSION_2_1 +/********************************* +* cl_khr_throttle_hints extension +*********************************/ +#define cl_khr_throttle_hints 1 + +typedef cl_uint cl_queue_throttle_khr; + +/* cl_command_queue_properties */ +#define CL_QUEUE_THROTTLE_KHR 0x1097 + +/* cl_queue_throttle_khr */ +#define CL_QUEUE_THROTTLE_HIGH_KHR (1<<0) +#define CL_QUEUE_THROTTLE_MED_KHR (1<<1) +#define CL_QUEUE_THROTTLE_LOW_KHR (1<<2) + +#endif /* CL_VERSION_2_1 */ + +#ifdef __cplusplus +} +#endif + + +#endif /* __CL_EXT_H */ diff --git a/phonelibs/opencl/include/CL/cl_gl.h b/phonelibs/opencl/include/CL/cl_gl.h new file mode 100644 index 00000000000000..945daa83d7f712 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_gl.h @@ -0,0 +1,167 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +#ifndef __OPENCL_CL_GL_H +#define __OPENCL_CL_GL_H + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef cl_uint cl_gl_object_type; +typedef cl_uint cl_gl_texture_info; +typedef cl_uint cl_gl_platform_info; +typedef struct __GLsync *cl_GLsync; + +/* cl_gl_object_type = 0x2000 - 0x200F enum values are currently taken */ +#define CL_GL_OBJECT_BUFFER 0x2000 +#define CL_GL_OBJECT_TEXTURE2D 0x2001 +#define CL_GL_OBJECT_TEXTURE3D 0x2002 +#define CL_GL_OBJECT_RENDERBUFFER 0x2003 +#define CL_GL_OBJECT_TEXTURE2D_ARRAY 0x200E +#define CL_GL_OBJECT_TEXTURE1D 0x200F +#define CL_GL_OBJECT_TEXTURE1D_ARRAY 0x2010 +#define CL_GL_OBJECT_TEXTURE_BUFFER 0x2011 + +/* cl_gl_texture_info */ +#define CL_GL_TEXTURE_TARGET 0x2004 +#define CL_GL_MIPMAP_LEVEL 0x2005 +#define CL_GL_NUM_SAMPLES 0x2012 + + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromGLBuffer(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLuint /* bufobj */, + int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromGLTexture(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLenum /* target */, + cl_GLint /* miplevel */, + cl_GLuint /* texture */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromGLRenderbuffer(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLuint /* renderbuffer */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetGLObjectInfo(cl_mem /* memobj */, + cl_gl_object_type * /* gl_object_type */, + cl_GLuint * /* gl_object_name */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetGLTextureInfo(cl_mem /* memobj */, + cl_gl_texture_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueAcquireGLObjects(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReleaseGLObjects(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + + +/* Deprecated OpenCL 1.1 APIs */ +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateFromGLTexture2D(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLenum /* target */, + cl_GLint /* miplevel */, + cl_GLuint /* texture */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateFromGLTexture3D(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLenum /* target */, + cl_GLint /* miplevel */, + cl_GLuint /* texture */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +/* cl_khr_gl_sharing extension */ + +#define cl_khr_gl_sharing 1 + +typedef cl_uint cl_gl_context_info; + +/* Additional Error Codes */ +#define CL_INVALID_GL_SHAREGROUP_REFERENCE_KHR -1000 + +/* cl_gl_context_info */ +#define CL_CURRENT_DEVICE_FOR_GL_CONTEXT_KHR 0x2006 +#define CL_DEVICES_FOR_GL_CONTEXT_KHR 0x2007 + +/* Additional cl_context_properties */ +#define CL_GL_CONTEXT_KHR 0x2008 +#define CL_EGL_DISPLAY_KHR 0x2009 +#define CL_GLX_DISPLAY_KHR 0x200A +#define CL_WGL_HDC_KHR 0x200B +#define CL_CGL_SHAREGROUP_KHR 0x200C + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetGLContextInfoKHR(const cl_context_properties * /* properties */, + cl_gl_context_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetGLContextInfoKHR_fn)( + const cl_context_properties * properties, + cl_gl_context_info param_name, + size_t param_value_size, + void * param_value, + size_t * param_value_size_ret); + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_GL_H */ diff --git a/phonelibs/opencl/include/CL/cl_gl_ext.h b/phonelibs/opencl/include/CL/cl_gl_ext.h new file mode 100644 index 00000000000000..e3c14c6408c441 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_gl_ext.h @@ -0,0 +1,74 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +/* cl_gl_ext.h contains vendor (non-KHR) OpenCL extensions which have */ +/* OpenGL dependencies. */ + +#ifndef __OPENCL_CL_GL_EXT_H +#define __OPENCL_CL_GL_EXT_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef __APPLE__ + #include +#else + #include +#endif + +/* + * For each extension, follow this template + * cl_VEN_extname extension */ +/* #define cl_VEN_extname 1 + * ... define new types, if any + * ... define new tokens, if any + * ... define new APIs, if any + * + * If you need GLtypes here, mirror them with a cl_GLtype, rather than including a GL header + * This allows us to avoid having to decide whether to include GL headers or GLES here. + */ + +/* + * cl_khr_gl_event extension + * See section 9.9 in the OpenCL 1.1 spec for more information + */ +#define CL_COMMAND_GL_FENCE_SYNC_OBJECT_KHR 0x200D + +extern CL_API_ENTRY cl_event CL_API_CALL +clCreateEventFromGLsyncKHR(cl_context /* context */, + cl_GLsync /* cl_GLsync */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_GL_EXT_H */ diff --git a/phonelibs/opencl/include/CL/cl_platform.h b/phonelibs/opencl/include/CL/cl_platform.h new file mode 100644 index 00000000000000..4e334a2918390d --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_platform.h @@ -0,0 +1,1333 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11803 $ on $Date: 2010-06-25 10:02:12 -0700 (Fri, 25 Jun 2010) $ */ + +#ifndef __CL_PLATFORM_H +#define __CL_PLATFORM_H + +#ifdef __APPLE__ + /* Contains #defines for AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER below */ + #include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined(_WIN32) + #define CL_API_ENTRY + #define CL_API_CALL __stdcall + #define CL_CALLBACK __stdcall +#else + #define CL_API_ENTRY + #define CL_API_CALL + #define CL_CALLBACK +#endif + +/* + * Deprecation flags refer to the last version of the header in which the + * feature was not deprecated. + * + * E.g. VERSION_1_1_DEPRECATED means the feature is present in 1.1 without + * deprecation but is deprecated in versions later than 1.1. + */ + +#ifdef __APPLE__ + #define CL_EXTENSION_WEAK_LINK __attribute__((weak_import)) + #define CL_API_SUFFIX__VERSION_1_0 AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_0 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER + #define CL_API_SUFFIX__VERSION_1_1 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define GCL_API_SUFFIX__VERSION_1_1 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_1 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER_BUT_DEPRECATED_IN_MAC_OS_X_VERSION_10_7 + + #ifdef AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define CL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define GCL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_2 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER_BUT_DEPRECATED_IN_MAC_OS_X_VERSION_10_8 + #else + #warning This path should never happen outside of internal operating system development. AvailabilityMacros do not function correctly here! + #define CL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define GCL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_2 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #endif +#else + #define CL_EXTENSION_WEAK_LINK + #define CL_API_SUFFIX__VERSION_1_0 + #define CL_EXT_SUFFIX__VERSION_1_0 + #define CL_API_SUFFIX__VERSION_1_1 + #define CL_EXT_SUFFIX__VERSION_1_1 + #define CL_API_SUFFIX__VERSION_1_2 + #define CL_EXT_SUFFIX__VERSION_1_2 + #define CL_API_SUFFIX__VERSION_2_0 + #define CL_EXT_SUFFIX__VERSION_2_0 + #define CL_API_SUFFIX__VERSION_2_1 + #define CL_EXT_SUFFIX__VERSION_2_1 + + #ifdef __GNUC__ + #ifdef CL_USE_DEPRECATED_OPENCL_1_0_APIS + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_1_APIS + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_2_APIS + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_2_0_APIS + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #endif + #elif _WIN32 + #ifdef CL_USE_DEPRECATED_OPENCL_1_0_APIS + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED __declspec(deprecated) + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_1_APIS + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED __declspec(deprecated) + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_2_APIS + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED __declspec(deprecated) + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_2_0_APIS + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED __declspec(deprecated) + #endif + #else + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #endif +#endif + +#if (defined (_WIN32) && defined(_MSC_VER)) + +/* scalar types */ +typedef signed __int8 cl_char; +typedef unsigned __int8 cl_uchar; +typedef signed __int16 cl_short; +typedef unsigned __int16 cl_ushort; +typedef signed __int32 cl_int; +typedef unsigned __int32 cl_uint; +typedef signed __int64 cl_long; +typedef unsigned __int64 cl_ulong; + +typedef unsigned __int16 cl_half; +typedef float cl_float; +typedef double cl_double; + +/* Macro names and corresponding values defined by OpenCL */ +#define CL_CHAR_BIT 8 +#define CL_SCHAR_MAX 127 +#define CL_SCHAR_MIN (-127-1) +#define CL_CHAR_MAX CL_SCHAR_MAX +#define CL_CHAR_MIN CL_SCHAR_MIN +#define CL_UCHAR_MAX 255 +#define CL_SHRT_MAX 32767 +#define CL_SHRT_MIN (-32767-1) +#define CL_USHRT_MAX 65535 +#define CL_INT_MAX 2147483647 +#define CL_INT_MIN (-2147483647-1) +#define CL_UINT_MAX 0xffffffffU +#define CL_LONG_MAX ((cl_long) 0x7FFFFFFFFFFFFFFFLL) +#define CL_LONG_MIN ((cl_long) -0x7FFFFFFFFFFFFFFFLL - 1LL) +#define CL_ULONG_MAX ((cl_ulong) 0xFFFFFFFFFFFFFFFFULL) + +#define CL_FLT_DIG 6 +#define CL_FLT_MANT_DIG 24 +#define CL_FLT_MAX_10_EXP +38 +#define CL_FLT_MAX_EXP +128 +#define CL_FLT_MIN_10_EXP -37 +#define CL_FLT_MIN_EXP -125 +#define CL_FLT_RADIX 2 +#define CL_FLT_MAX 340282346638528859811704183484516925440.0f +#define CL_FLT_MIN 1.175494350822287507969e-38f +#define CL_FLT_EPSILON 0x1.0p-23f + +#define CL_DBL_DIG 15 +#define CL_DBL_MANT_DIG 53 +#define CL_DBL_MAX_10_EXP +308 +#define CL_DBL_MAX_EXP +1024 +#define CL_DBL_MIN_10_EXP -307 +#define CL_DBL_MIN_EXP -1021 +#define CL_DBL_RADIX 2 +#define CL_DBL_MAX 179769313486231570814527423731704356798070567525844996598917476803157260780028538760589558632766878171540458953514382464234321326889464182768467546703537516986049910576551282076245490090389328944075868508455133942304583236903222948165808559332123348274797826204144723168738177180919299881250404026184124858368.0 +#define CL_DBL_MIN 2.225073858507201383090e-308 +#define CL_DBL_EPSILON 2.220446049250313080847e-16 + +#define CL_M_E 2.718281828459045090796 +#define CL_M_LOG2E 1.442695040888963387005 +#define CL_M_LOG10E 0.434294481903251816668 +#define CL_M_LN2 0.693147180559945286227 +#define CL_M_LN10 2.302585092994045901094 +#define CL_M_PI 3.141592653589793115998 +#define CL_M_PI_2 1.570796326794896557999 +#define CL_M_PI_4 0.785398163397448278999 +#define CL_M_1_PI 0.318309886183790691216 +#define CL_M_2_PI 0.636619772367581382433 +#define CL_M_2_SQRTPI 1.128379167095512558561 +#define CL_M_SQRT2 1.414213562373095145475 +#define CL_M_SQRT1_2 0.707106781186547572737 + +#define CL_M_E_F 2.71828174591064f +#define CL_M_LOG2E_F 1.44269502162933f +#define CL_M_LOG10E_F 0.43429449200630f +#define CL_M_LN2_F 0.69314718246460f +#define CL_M_LN10_F 2.30258512496948f +#define CL_M_PI_F 3.14159274101257f +#define CL_M_PI_2_F 1.57079637050629f +#define CL_M_PI_4_F 0.78539818525314f +#define CL_M_1_PI_F 0.31830987334251f +#define CL_M_2_PI_F 0.63661974668503f +#define CL_M_2_SQRTPI_F 1.12837922573090f +#define CL_M_SQRT2_F 1.41421353816986f +#define CL_M_SQRT1_2_F 0.70710676908493f + +#define CL_NAN (CL_INFINITY - CL_INFINITY) +#define CL_HUGE_VALF ((cl_float) 1e50) +#define CL_HUGE_VAL ((cl_double) 1e500) +#define CL_MAXFLOAT CL_FLT_MAX +#define CL_INFINITY CL_HUGE_VALF + +#else + +#include + +/* scalar types */ +typedef int8_t cl_char; +typedef uint8_t cl_uchar; +typedef int16_t cl_short __attribute__((aligned(2))); +typedef uint16_t cl_ushort __attribute__((aligned(2))); +typedef int32_t cl_int __attribute__((aligned(4))); +typedef uint32_t cl_uint __attribute__((aligned(4))); +typedef int64_t cl_long __attribute__((aligned(8))); +typedef uint64_t cl_ulong __attribute__((aligned(8))); + +typedef uint16_t cl_half __attribute__((aligned(2))); +typedef float cl_float __attribute__((aligned(4))); +typedef double cl_double __attribute__((aligned(8))); + +/* Macro names and corresponding values defined by OpenCL */ +#define CL_CHAR_BIT 8 +#define CL_SCHAR_MAX 127 +#define CL_SCHAR_MIN (-127-1) +#define CL_CHAR_MAX CL_SCHAR_MAX +#define CL_CHAR_MIN CL_SCHAR_MIN +#define CL_UCHAR_MAX 255 +#define CL_SHRT_MAX 32767 +#define CL_SHRT_MIN (-32767-1) +#define CL_USHRT_MAX 65535 +#define CL_INT_MAX 2147483647 +#define CL_INT_MIN (-2147483647-1) +#define CL_UINT_MAX 0xffffffffU +#define CL_LONG_MAX ((cl_long) 0x7FFFFFFFFFFFFFFFLL) +#define CL_LONG_MIN ((cl_long) -0x7FFFFFFFFFFFFFFFLL - 1LL) +#define CL_ULONG_MAX ((cl_ulong) 0xFFFFFFFFFFFFFFFFULL) + +#define CL_FLT_DIG 6 +#define CL_FLT_MANT_DIG 24 +#define CL_FLT_MAX_10_EXP +38 +#define CL_FLT_MAX_EXP +128 +#define CL_FLT_MIN_10_EXP -37 +#define CL_FLT_MIN_EXP -125 +#define CL_FLT_RADIX 2 +#define CL_FLT_MAX 0x1.fffffep127f +#define CL_FLT_MIN 0x1.0p-126f +#define CL_FLT_EPSILON 0x1.0p-23f + +#define CL_DBL_DIG 15 +#define CL_DBL_MANT_DIG 53 +#define CL_DBL_MAX_10_EXP +308 +#define CL_DBL_MAX_EXP +1024 +#define CL_DBL_MIN_10_EXP -307 +#define CL_DBL_MIN_EXP -1021 +#define CL_DBL_RADIX 2 +#define CL_DBL_MAX 0x1.fffffffffffffp1023 +#define CL_DBL_MIN 0x1.0p-1022 +#define CL_DBL_EPSILON 0x1.0p-52 + +#define CL_M_E 2.718281828459045090796 +#define CL_M_LOG2E 1.442695040888963387005 +#define CL_M_LOG10E 0.434294481903251816668 +#define CL_M_LN2 0.693147180559945286227 +#define CL_M_LN10 2.302585092994045901094 +#define CL_M_PI 3.141592653589793115998 +#define CL_M_PI_2 1.570796326794896557999 +#define CL_M_PI_4 0.785398163397448278999 +#define CL_M_1_PI 0.318309886183790691216 +#define CL_M_2_PI 0.636619772367581382433 +#define CL_M_2_SQRTPI 1.128379167095512558561 +#define CL_M_SQRT2 1.414213562373095145475 +#define CL_M_SQRT1_2 0.707106781186547572737 + +#define CL_M_E_F 2.71828174591064f +#define CL_M_LOG2E_F 1.44269502162933f +#define CL_M_LOG10E_F 0.43429449200630f +#define CL_M_LN2_F 0.69314718246460f +#define CL_M_LN10_F 2.30258512496948f +#define CL_M_PI_F 3.14159274101257f +#define CL_M_PI_2_F 1.57079637050629f +#define CL_M_PI_4_F 0.78539818525314f +#define CL_M_1_PI_F 0.31830987334251f +#define CL_M_2_PI_F 0.63661974668503f +#define CL_M_2_SQRTPI_F 1.12837922573090f +#define CL_M_SQRT2_F 1.41421353816986f +#define CL_M_SQRT1_2_F 0.70710676908493f + +#if defined( __GNUC__ ) + #define CL_HUGE_VALF __builtin_huge_valf() + #define CL_HUGE_VAL __builtin_huge_val() + #define CL_NAN __builtin_nanf( "" ) +#else + #define CL_HUGE_VALF ((cl_float) 1e50) + #define CL_HUGE_VAL ((cl_double) 1e500) + float nanf( const char * ); + #define CL_NAN nanf( "" ) +#endif +#define CL_MAXFLOAT CL_FLT_MAX +#define CL_INFINITY CL_HUGE_VALF + +#endif + +#include + +/* Mirror types to GL types. Mirror types allow us to avoid deciding which 87s to load based on whether we are using GL or GLES here. */ +typedef unsigned int cl_GLuint; +typedef int cl_GLint; +typedef unsigned int cl_GLenum; + +/* + * Vector types + * + * Note: OpenCL requires that all types be naturally aligned. + * This means that vector types must be naturally aligned. + * For example, a vector of four floats must be aligned to + * a 16 byte boundary (calculated as 4 * the natural 4-byte + * alignment of the float). The alignment qualifiers here + * will only function properly if your compiler supports them + * and if you don't actively work to defeat them. For example, + * in order for a cl_float4 to be 16 byte aligned in a struct, + * the start of the struct must itself be 16-byte aligned. + * + * Maintaining proper alignment is the user's responsibility. + */ + +/* Define basic vector types */ +#if defined( __VEC__ ) + #include /* may be omitted depending on compiler. AltiVec spec provides no way to detect whether the header is required. */ + typedef vector unsigned char __cl_uchar16; + typedef vector signed char __cl_char16; + typedef vector unsigned short __cl_ushort8; + typedef vector signed short __cl_short8; + typedef vector unsigned int __cl_uint4; + typedef vector signed int __cl_int4; + typedef vector float __cl_float4; + #define __CL_UCHAR16__ 1 + #define __CL_CHAR16__ 1 + #define __CL_USHORT8__ 1 + #define __CL_SHORT8__ 1 + #define __CL_UINT4__ 1 + #define __CL_INT4__ 1 + #define __CL_FLOAT4__ 1 +#endif + +#if defined( __SSE__ ) + #if defined( __MINGW64__ ) + #include + #else + #include + #endif + #if defined( __GNUC__ ) + typedef float __cl_float4 __attribute__((vector_size(16))); + #else + typedef __m128 __cl_float4; + #endif + #define __CL_FLOAT4__ 1 +#endif + +#if defined( __SSE2__ ) + #if defined( __MINGW64__ ) + #include + #else + #include + #endif + #if defined( __GNUC__ ) + typedef cl_uchar __cl_uchar16 __attribute__((vector_size(16))); + typedef cl_char __cl_char16 __attribute__((vector_size(16))); + typedef cl_ushort __cl_ushort8 __attribute__((vector_size(16))); + typedef cl_short __cl_short8 __attribute__((vector_size(16))); + typedef cl_uint __cl_uint4 __attribute__((vector_size(16))); + typedef cl_int __cl_int4 __attribute__((vector_size(16))); + typedef cl_ulong __cl_ulong2 __attribute__((vector_size(16))); + typedef cl_long __cl_long2 __attribute__((vector_size(16))); + typedef cl_double __cl_double2 __attribute__((vector_size(16))); + #else + typedef __m128i __cl_uchar16; + typedef __m128i __cl_char16; + typedef __m128i __cl_ushort8; + typedef __m128i __cl_short8; + typedef __m128i __cl_uint4; + typedef __m128i __cl_int4; + typedef __m128i __cl_ulong2; + typedef __m128i __cl_long2; + typedef __m128d __cl_double2; + #endif + #define __CL_UCHAR16__ 1 + #define __CL_CHAR16__ 1 + #define __CL_USHORT8__ 1 + #define __CL_SHORT8__ 1 + #define __CL_INT4__ 1 + #define __CL_UINT4__ 1 + #define __CL_ULONG2__ 1 + #define __CL_LONG2__ 1 + #define __CL_DOUBLE2__ 1 +#endif + +#if defined( __MMX__ ) + #include + #if defined( __GNUC__ ) + typedef cl_uchar __cl_uchar8 __attribute__((vector_size(8))); + typedef cl_char __cl_char8 __attribute__((vector_size(8))); + typedef cl_ushort __cl_ushort4 __attribute__((vector_size(8))); + typedef cl_short __cl_short4 __attribute__((vector_size(8))); + typedef cl_uint __cl_uint2 __attribute__((vector_size(8))); + typedef cl_int __cl_int2 __attribute__((vector_size(8))); + typedef cl_ulong __cl_ulong1 __attribute__((vector_size(8))); + typedef cl_long __cl_long1 __attribute__((vector_size(8))); + typedef cl_float __cl_float2 __attribute__((vector_size(8))); + #else + typedef __m64 __cl_uchar8; + typedef __m64 __cl_char8; + typedef __m64 __cl_ushort4; + typedef __m64 __cl_short4; + typedef __m64 __cl_uint2; + typedef __m64 __cl_int2; + typedef __m64 __cl_ulong1; + typedef __m64 __cl_long1; + typedef __m64 __cl_float2; + #endif + #define __CL_UCHAR8__ 1 + #define __CL_CHAR8__ 1 + #define __CL_USHORT4__ 1 + #define __CL_SHORT4__ 1 + #define __CL_INT2__ 1 + #define __CL_UINT2__ 1 + #define __CL_ULONG1__ 1 + #define __CL_LONG1__ 1 + #define __CL_FLOAT2__ 1 +#endif + +#if defined( __AVX__ ) + #if defined( __MINGW64__ ) + #include + #else + #include + #endif + #if defined( __GNUC__ ) + typedef cl_float __cl_float8 __attribute__((vector_size(32))); + typedef cl_double __cl_double4 __attribute__((vector_size(32))); + #else + typedef __m256 __cl_float8; + typedef __m256d __cl_double4; + #endif + #define __CL_FLOAT8__ 1 + #define __CL_DOUBLE4__ 1 +#endif + +/* Define capabilities for anonymous struct members. */ +#if defined( __GNUC__) && ! defined( __STRICT_ANSI__ ) +#define __CL_HAS_ANON_STRUCT__ 1 +#define __CL_ANON_STRUCT__ __extension__ +#elif defined( _WIN32) && (_MSC_VER >= 1500) + /* Microsoft Developer Studio 2008 supports anonymous structs, but + * complains by default. */ +#define __CL_HAS_ANON_STRUCT__ 1 +#define __CL_ANON_STRUCT__ + /* Disable warning C4201: nonstandard extension used : nameless + * struct/union */ +#pragma warning( push ) +#pragma warning( disable : 4201 ) +#else +#define __CL_HAS_ANON_STRUCT__ 0 +#define __CL_ANON_STRUCT__ +#endif + +/* Define alignment keys */ +#if defined( __GNUC__ ) + #define CL_ALIGNED(_x) __attribute__ ((aligned(_x))) +#elif defined( _WIN32) && (_MSC_VER) + /* Alignment keys neutered on windows because MSVC can't swallow function arguments with alignment requirements */ + /* http://msdn.microsoft.com/en-us/library/373ak2y1%28VS.71%29.aspx */ + /* #include */ + /* #define CL_ALIGNED(_x) _CRT_ALIGN(_x) */ + #define CL_ALIGNED(_x) +#else + #warning Need to implement some method to align data here + #define CL_ALIGNED(_x) +#endif + +/* Indicate whether .xyzw, .s0123 and .hi.lo are supported */ +#if __CL_HAS_ANON_STRUCT__ + /* .xyzw and .s0123...{f|F} are supported */ + #define CL_HAS_NAMED_VECTOR_FIELDS 1 + /* .hi and .lo are supported */ + #define CL_HAS_HI_LO_VECTOR_FIELDS 1 +#endif + +/* Define cl_vector types */ + +/* ---- cl_charn ---- */ +typedef union +{ + cl_char CL_ALIGNED(2) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_char lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2; +#endif +}cl_char2; + +typedef union +{ + cl_char CL_ALIGNED(4) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_char2 lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2[2]; +#endif +#if defined( __CL_CHAR4__) + __cl_char4 v4; +#endif +}cl_char4; + +/* cl_char3 is identical in size, alignment and behavior to cl_char4. See section 6.1.5. */ +typedef cl_char4 cl_char3; + +typedef union +{ + cl_char CL_ALIGNED(8) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_char4 lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2[4]; +#endif +#if defined( __CL_CHAR4__) + __cl_char4 v4[2]; +#endif +#if defined( __CL_CHAR8__ ) + __cl_char8 v8; +#endif +}cl_char8; + +typedef union +{ + cl_char CL_ALIGNED(16) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_char8 lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2[8]; +#endif +#if defined( __CL_CHAR4__) + __cl_char4 v4[4]; +#endif +#if defined( __CL_CHAR8__ ) + __cl_char8 v8[2]; +#endif +#if defined( __CL_CHAR16__ ) + __cl_char16 v16; +#endif +}cl_char16; + + +/* ---- cl_ucharn ---- */ +typedef union +{ + cl_uchar CL_ALIGNED(2) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_uchar lo, hi; }; +#endif +#if defined( __cl_uchar2__) + __cl_uchar2 v2; +#endif +}cl_uchar2; + +typedef union +{ + cl_uchar CL_ALIGNED(4) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_uchar2 lo, hi; }; +#endif +#if defined( __CL_UCHAR2__) + __cl_uchar2 v2[2]; +#endif +#if defined( __CL_UCHAR4__) + __cl_uchar4 v4; +#endif +}cl_uchar4; + +/* cl_uchar3 is identical in size, alignment and behavior to cl_uchar4. See section 6.1.5. */ +typedef cl_uchar4 cl_uchar3; + +typedef union +{ + cl_uchar CL_ALIGNED(8) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_uchar4 lo, hi; }; +#endif +#if defined( __CL_UCHAR2__) + __cl_uchar2 v2[4]; +#endif +#if defined( __CL_UCHAR4__) + __cl_uchar4 v4[2]; +#endif +#if defined( __CL_UCHAR8__ ) + __cl_uchar8 v8; +#endif +}cl_uchar8; + +typedef union +{ + cl_uchar CL_ALIGNED(16) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_uchar8 lo, hi; }; +#endif +#if defined( __CL_UCHAR2__) + __cl_uchar2 v2[8]; +#endif +#if defined( __CL_UCHAR4__) + __cl_uchar4 v4[4]; +#endif +#if defined( __CL_UCHAR8__ ) + __cl_uchar8 v8[2]; +#endif +#if defined( __CL_UCHAR16__ ) + __cl_uchar16 v16; +#endif +}cl_uchar16; + + +/* ---- cl_shortn ---- */ +typedef union +{ + cl_short CL_ALIGNED(4) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_short lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2; +#endif +}cl_short2; + +typedef union +{ + cl_short CL_ALIGNED(8) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_short2 lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2[2]; +#endif +#if defined( __CL_SHORT4__) + __cl_short4 v4; +#endif +}cl_short4; + +/* cl_short3 is identical in size, alignment and behavior to cl_short4. See section 6.1.5. */ +typedef cl_short4 cl_short3; + +typedef union +{ + cl_short CL_ALIGNED(16) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_short4 lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2[4]; +#endif +#if defined( __CL_SHORT4__) + __cl_short4 v4[2]; +#endif +#if defined( __CL_SHORT8__ ) + __cl_short8 v8; +#endif +}cl_short8; + +typedef union +{ + cl_short CL_ALIGNED(32) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_short8 lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2[8]; +#endif +#if defined( __CL_SHORT4__) + __cl_short4 v4[4]; +#endif +#if defined( __CL_SHORT8__ ) + __cl_short8 v8[2]; +#endif +#if defined( __CL_SHORT16__ ) + __cl_short16 v16; +#endif +}cl_short16; + + +/* ---- cl_ushortn ---- */ +typedef union +{ + cl_ushort CL_ALIGNED(4) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_ushort lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2; +#endif +}cl_ushort2; + +typedef union +{ + cl_ushort CL_ALIGNED(8) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_ushort2 lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2[2]; +#endif +#if defined( __CL_USHORT4__) + __cl_ushort4 v4; +#endif +}cl_ushort4; + +/* cl_ushort3 is identical in size, alignment and behavior to cl_ushort4. See section 6.1.5. */ +typedef cl_ushort4 cl_ushort3; + +typedef union +{ + cl_ushort CL_ALIGNED(16) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_ushort4 lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2[4]; +#endif +#if defined( __CL_USHORT4__) + __cl_ushort4 v4[2]; +#endif +#if defined( __CL_USHORT8__ ) + __cl_ushort8 v8; +#endif +}cl_ushort8; + +typedef union +{ + cl_ushort CL_ALIGNED(32) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_ushort8 lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2[8]; +#endif +#if defined( __CL_USHORT4__) + __cl_ushort4 v4[4]; +#endif +#if defined( __CL_USHORT8__ ) + __cl_ushort8 v8[2]; +#endif +#if defined( __CL_USHORT16__ ) + __cl_ushort16 v16; +#endif +}cl_ushort16; + +/* ---- cl_intn ---- */ +typedef union +{ + cl_int CL_ALIGNED(8) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_int lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2; +#endif +}cl_int2; + +typedef union +{ + cl_int CL_ALIGNED(16) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_int2 lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2[2]; +#endif +#if defined( __CL_INT4__) + __cl_int4 v4; +#endif +}cl_int4; + +/* cl_int3 is identical in size, alignment and behavior to cl_int4. See section 6.1.5. */ +typedef cl_int4 cl_int3; + +typedef union +{ + cl_int CL_ALIGNED(32) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_int4 lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2[4]; +#endif +#if defined( __CL_INT4__) + __cl_int4 v4[2]; +#endif +#if defined( __CL_INT8__ ) + __cl_int8 v8; +#endif +}cl_int8; + +typedef union +{ + cl_int CL_ALIGNED(64) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_int8 lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2[8]; +#endif +#if defined( __CL_INT4__) + __cl_int4 v4[4]; +#endif +#if defined( __CL_INT8__ ) + __cl_int8 v8[2]; +#endif +#if defined( __CL_INT16__ ) + __cl_int16 v16; +#endif +}cl_int16; + + +/* ---- cl_uintn ---- */ +typedef union +{ + cl_uint CL_ALIGNED(8) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_uint lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2; +#endif +}cl_uint2; + +typedef union +{ + cl_uint CL_ALIGNED(16) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_uint2 lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2[2]; +#endif +#if defined( __CL_UINT4__) + __cl_uint4 v4; +#endif +}cl_uint4; + +/* cl_uint3 is identical in size, alignment and behavior to cl_uint4. See section 6.1.5. */ +typedef cl_uint4 cl_uint3; + +typedef union +{ + cl_uint CL_ALIGNED(32) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_uint4 lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2[4]; +#endif +#if defined( __CL_UINT4__) + __cl_uint4 v4[2]; +#endif +#if defined( __CL_UINT8__ ) + __cl_uint8 v8; +#endif +}cl_uint8; + +typedef union +{ + cl_uint CL_ALIGNED(64) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_uint8 lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2[8]; +#endif +#if defined( __CL_UINT4__) + __cl_uint4 v4[4]; +#endif +#if defined( __CL_UINT8__ ) + __cl_uint8 v8[2]; +#endif +#if defined( __CL_UINT16__ ) + __cl_uint16 v16; +#endif +}cl_uint16; + +/* ---- cl_longn ---- */ +typedef union +{ + cl_long CL_ALIGNED(16) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_long lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2; +#endif +}cl_long2; + +typedef union +{ + cl_long CL_ALIGNED(32) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_long2 lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2[2]; +#endif +#if defined( __CL_LONG4__) + __cl_long4 v4; +#endif +}cl_long4; + +/* cl_long3 is identical in size, alignment and behavior to cl_long4. See section 6.1.5. */ +typedef cl_long4 cl_long3; + +typedef union +{ + cl_long CL_ALIGNED(64) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_long4 lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2[4]; +#endif +#if defined( __CL_LONG4__) + __cl_long4 v4[2]; +#endif +#if defined( __CL_LONG8__ ) + __cl_long8 v8; +#endif +}cl_long8; + +typedef union +{ + cl_long CL_ALIGNED(128) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_long8 lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2[8]; +#endif +#if defined( __CL_LONG4__) + __cl_long4 v4[4]; +#endif +#if defined( __CL_LONG8__ ) + __cl_long8 v8[2]; +#endif +#if defined( __CL_LONG16__ ) + __cl_long16 v16; +#endif +}cl_long16; + + +/* ---- cl_ulongn ---- */ +typedef union +{ + cl_ulong CL_ALIGNED(16) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_ulong lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2; +#endif +}cl_ulong2; + +typedef union +{ + cl_ulong CL_ALIGNED(32) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_ulong2 lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2[2]; +#endif +#if defined( __CL_ULONG4__) + __cl_ulong4 v4; +#endif +}cl_ulong4; + +/* cl_ulong3 is identical in size, alignment and behavior to cl_ulong4. See section 6.1.5. */ +typedef cl_ulong4 cl_ulong3; + +typedef union +{ + cl_ulong CL_ALIGNED(64) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_ulong4 lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2[4]; +#endif +#if defined( __CL_ULONG4__) + __cl_ulong4 v4[2]; +#endif +#if defined( __CL_ULONG8__ ) + __cl_ulong8 v8; +#endif +}cl_ulong8; + +typedef union +{ + cl_ulong CL_ALIGNED(128) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_ulong8 lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2[8]; +#endif +#if defined( __CL_ULONG4__) + __cl_ulong4 v4[4]; +#endif +#if defined( __CL_ULONG8__ ) + __cl_ulong8 v8[2]; +#endif +#if defined( __CL_ULONG16__ ) + __cl_ulong16 v16; +#endif +}cl_ulong16; + + +/* --- cl_floatn ---- */ + +typedef union +{ + cl_float CL_ALIGNED(8) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_float lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2; +#endif +}cl_float2; + +typedef union +{ + cl_float CL_ALIGNED(16) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_float2 lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2[2]; +#endif +#if defined( __CL_FLOAT4__) + __cl_float4 v4; +#endif +}cl_float4; + +/* cl_float3 is identical in size, alignment and behavior to cl_float4. See section 6.1.5. */ +typedef cl_float4 cl_float3; + +typedef union +{ + cl_float CL_ALIGNED(32) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_float4 lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2[4]; +#endif +#if defined( __CL_FLOAT4__) + __cl_float4 v4[2]; +#endif +#if defined( __CL_FLOAT8__ ) + __cl_float8 v8; +#endif +}cl_float8; + +typedef union +{ + cl_float CL_ALIGNED(64) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_float8 lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2[8]; +#endif +#if defined( __CL_FLOAT4__) + __cl_float4 v4[4]; +#endif +#if defined( __CL_FLOAT8__ ) + __cl_float8 v8[2]; +#endif +#if defined( __CL_FLOAT16__ ) + __cl_float16 v16; +#endif +}cl_float16; + +/* --- cl_doublen ---- */ + +typedef union +{ + cl_double CL_ALIGNED(16) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_double lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2; +#endif +}cl_double2; + +typedef union +{ + cl_double CL_ALIGNED(32) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_double2 lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2[2]; +#endif +#if defined( __CL_DOUBLE4__) + __cl_double4 v4; +#endif +}cl_double4; + +/* cl_double3 is identical in size, alignment and behavior to cl_double4. See section 6.1.5. */ +typedef cl_double4 cl_double3; + +typedef union +{ + cl_double CL_ALIGNED(64) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_double4 lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2[4]; +#endif +#if defined( __CL_DOUBLE4__) + __cl_double4 v4[2]; +#endif +#if defined( __CL_DOUBLE8__ ) + __cl_double8 v8; +#endif +}cl_double8; + +typedef union +{ + cl_double CL_ALIGNED(128) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_double8 lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2[8]; +#endif +#if defined( __CL_DOUBLE4__) + __cl_double4 v4[4]; +#endif +#if defined( __CL_DOUBLE8__ ) + __cl_double8 v8[2]; +#endif +#if defined( __CL_DOUBLE16__ ) + __cl_double16 v16; +#endif +}cl_double16; + +/* Macro to facilitate debugging + * Usage: + * Place CL_PROGRAM_STRING_DEBUG_INFO on the line before the first line of your source. + * The first line ends with: CL_PROGRAM_STRING_DEBUG_INFO \" + * Each line thereafter of OpenCL C source must end with: \n\ + * The last line ends in "; + * + * Example: + * + * const char *my_program = CL_PROGRAM_STRING_DEBUG_INFO "\ + * kernel void foo( int a, float * b ) \n\ + * { \n\ + * // my comment \n\ + * *b[ get_global_id(0)] = a; \n\ + * } \n\ + * "; + * + * This should correctly set up the line, (column) and file information for your source + * string so you can do source level debugging. + */ +#define __CL_STRINGIFY( _x ) # _x +#define _CL_STRINGIFY( _x ) __CL_STRINGIFY( _x ) +#define CL_PROGRAM_STRING_DEBUG_INFO "#line " _CL_STRINGIFY(__LINE__) " \"" __FILE__ "\" \n\n" + +#ifdef __cplusplus +} +#endif + +#undef __CL_HAS_ANON_STRUCT__ +#undef __CL_ANON_STRUCT__ +#if defined( _WIN32) && (_MSC_VER >= 1500) +#pragma warning( pop ) +#endif + +#endif /* __CL_PLATFORM_H */ diff --git a/phonelibs/opencl/include/CL/opencl.h b/phonelibs/opencl/include/CL/opencl.h new file mode 100644 index 00000000000000..9855cd75e7da06 --- /dev/null +++ b/phonelibs/opencl/include/CL/opencl.h @@ -0,0 +1,59 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_H +#define __OPENCL_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef __APPLE__ + +#include +#include +#include +#include + +#else + +#include +#include +#include +#include + +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_H */ + diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/PKG-INFO b/pyextra/Flask-1.0.2-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..59a627f61ca490 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/PKG-INFO @@ -0,0 +1,103 @@ +Metadata-Version: 1.1 +Name: Flask +Version: 1.0.2 +Summary: A simple framework for building complex web applications. +Home-page: https://www.palletsprojects.com/p/flask/ +Author: Pallets team +Author-email: contact@palletsprojects.com +License: BSD +Description: Flask + ===== + + Flask is a lightweight `WSGI`_ web application framework. It is designed + to make getting started quick and easy, with the ability to scale up to + complex applications. It began as a simple wrapper around `Werkzeug`_ + and `Jinja`_ and has become one of the most popular Python web + application frameworks. + + Flask offers suggestions, but doesn't enforce any dependencies or + project layout. It is up to the developer to choose the tools and + libraries they want to use. There are many extensions provided by the + community that make adding new functionality easy. + + + Installing + ---------- + + Install and update using `pip`_: + + .. code-block:: text + + pip install -U Flask + + + A Simple Example + ---------------- + + .. code-block:: python + + from flask import Flask + + app = Flask(__name__) + + @app.route('/') + def hello(): + return 'Hello, World!' + + .. code-block:: text + + $ FLASK_APP=hello.py flask run + * Serving Flask app "hello" + * Running on http://127.0.0.1:5000/ (Press CTRL+C to quit) + + + Donate + ------ + + The Pallets organization develops and supports Flask and the libraries + it uses. In order to grow the community of contributors and users, and + allow the maintainers to devote more time to the projects, `please + donate today`_. + + .. _please donate today: https://psfmember.org/civicrm/contribute/transact?reset=1&id=20 + + + Links + ----- + + * Website: https://www.palletsprojects.com/p/flask/ + * Documentation: http://flask.pocoo.org/docs/ + * License: `BSD `_ + * Releases: https://pypi.org/project/Flask/ + * Code: https://github.com/pallets/flask + * Issue tracker: https://github.com/pallets/flask/issues + * Test status: + + * Linux, Mac: https://travis-ci.org/pallets/flask + * Windows: https://ci.appveyor.com/project/pallets/flask + + * Test coverage: https://codecov.io/gh/pallets/flask + + .. _WSGI: https://wsgi.readthedocs.io + .. _Werkzeug: https://www.palletsprojects.com/p/werkzeug/ + .. _Jinja: https://www.palletsprojects.com/p/jinja/ + .. _pip: https://pip.pypa.io/en/stable/quickstart/ + +Platform: any +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Framework :: Flask +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 2 +Classifier: Programming Language :: Python :: 2.7 +Classifier: Programming Language :: Python :: 3 +Classifier: Programming Language :: Python :: 3.4 +Classifier: Programming Language :: Python :: 3.5 +Classifier: Programming Language :: Python :: 3.6 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Internet :: WWW/HTTP :: WSGI :: Application +Classifier: Topic :: Software Development :: Libraries :: Application Frameworks +Classifier: Topic :: Software Development :: Libraries :: Python Modules diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/SOURCES.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..52f6db1918a045 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,223 @@ +AUTHORS +CHANGES.rst +LICENSE +MANIFEST.in +Makefile +README.rst +setup.cfg +setup.py +tox.ini +Flask.egg-info/PKG-INFO +Flask.egg-info/SOURCES.txt +Flask.egg-info/dependency_links.txt +Flask.egg-info/entry_points.txt +Flask.egg-info/not-zip-safe +Flask.egg-info/requires.txt +Flask.egg-info/top_level.txt +artwork/LICENSE +artwork/logo-full.svg +artwork/logo-lineart.svg +docs/Makefile +docs/advanced_foreword.rst +docs/api.rst +docs/appcontext.rst +docs/becomingbig.rst +docs/blueprints.rst +docs/changelog.rst +docs/cli.rst +docs/conf.py +docs/config.rst +docs/contents.rst.inc +docs/contributing.rst +docs/design.rst +docs/errorhandling.rst +docs/extensiondev.rst +docs/extensions.rst +docs/flaskstyle.sty +docs/foreword.rst +docs/htmlfaq.rst +docs/index.rst +docs/installation.rst +docs/latexindex.rst +docs/license.rst +docs/logging.rst +docs/logo.pdf +docs/make.bat +docs/quickstart.rst +docs/reqcontext.rst +docs/security.rst +docs/server.rst +docs/shell.rst +docs/signals.rst +docs/styleguide.rst +docs/templating.rst +docs/testing.rst +docs/unicode.rst +docs/upgrading.rst +docs/views.rst +docs/_static/debugger.png +docs/_static/flask-favicon.ico +docs/_static/flask.png +docs/_static/logo-full.png +docs/_static/no.png +docs/_static/pycharm-runconfig.png +docs/_static/touch-icon.png +docs/_static/yes.png +docs/deploying/cgi.rst +docs/deploying/fastcgi.rst +docs/deploying/index.rst +docs/deploying/mod_wsgi.rst +docs/deploying/uwsgi.rst +docs/deploying/wsgi-standalone.rst +docs/patterns/apierrors.rst +docs/patterns/appdispatch.rst +docs/patterns/appfactories.rst +docs/patterns/caching.rst +docs/patterns/celery.rst +docs/patterns/deferredcallbacks.rst +docs/patterns/distribute.rst +docs/patterns/errorpages.rst +docs/patterns/fabric.rst +docs/patterns/favicon.rst +docs/patterns/fileuploads.rst +docs/patterns/flashing.rst +docs/patterns/index.rst +docs/patterns/jquery.rst +docs/patterns/lazyloading.rst +docs/patterns/methodoverrides.rst +docs/patterns/mongokit.rst +docs/patterns/packages.rst +docs/patterns/requestchecksum.rst +docs/patterns/sqlalchemy.rst +docs/patterns/sqlite3.rst +docs/patterns/streaming.rst +docs/patterns/subclassing.rst +docs/patterns/templateinheritance.rst +docs/patterns/urlprocessors.rst +docs/patterns/viewdecorators.rst +docs/patterns/wtforms.rst +docs/tutorial/blog.rst +docs/tutorial/database.rst +docs/tutorial/deploy.rst +docs/tutorial/factory.rst +docs/tutorial/flaskr_edit.png +docs/tutorial/flaskr_index.png +docs/tutorial/flaskr_login.png +docs/tutorial/index.rst +docs/tutorial/install.rst +docs/tutorial/layout.rst +docs/tutorial/next.rst +docs/tutorial/static.rst +docs/tutorial/templates.rst +docs/tutorial/tests.rst +docs/tutorial/views.rst +examples/javascript/.gitignore +examples/javascript/LICENSE +examples/javascript/MANIFEST.in +examples/javascript/README.rst +examples/javascript/setup.cfg +examples/javascript/setup.py +examples/javascript/js_example/__init__.py +examples/javascript/js_example/views.py +examples/javascript/js_example/templates/base.html +examples/javascript/js_example/templates/fetch.html +examples/javascript/js_example/templates/jquery.html +examples/javascript/js_example/templates/plain.html +examples/javascript/tests/conftest.py +examples/javascript/tests/test_js_example.py +examples/tutorial/.gitignore +examples/tutorial/LICENSE +examples/tutorial/MANIFEST.in +examples/tutorial/README.rst +examples/tutorial/setup.cfg +examples/tutorial/setup.py +examples/tutorial/flaskr/__init__.py +examples/tutorial/flaskr/auth.py +examples/tutorial/flaskr/blog.py +examples/tutorial/flaskr/db.py +examples/tutorial/flaskr/schema.sql +examples/tutorial/flaskr/static/style.css +examples/tutorial/flaskr/templates/base.html +examples/tutorial/flaskr/templates/auth/login.html +examples/tutorial/flaskr/templates/auth/register.html +examples/tutorial/flaskr/templates/blog/create.html +examples/tutorial/flaskr/templates/blog/index.html +examples/tutorial/flaskr/templates/blog/update.html +examples/tutorial/tests/conftest.py +examples/tutorial/tests/data.sql +examples/tutorial/tests/test_auth.py +examples/tutorial/tests/test_blog.py +examples/tutorial/tests/test_db.py +examples/tutorial/tests/test_factory.py +flask/__init__.py +flask/__main__.py +flask/_compat.py +flask/app.py +flask/blueprints.py +flask/cli.py +flask/config.py +flask/ctx.py +flask/debughelpers.py +flask/globals.py +flask/helpers.py +flask/logging.py +flask/sessions.py +flask/signals.py +flask/templating.py +flask/testing.py +flask/views.py +flask/wrappers.py +flask/json/__init__.py +flask/json/tag.py +tests/conftest.py +tests/test_appctx.py +tests/test_basic.py +tests/test_blueprints.py +tests/test_cli.py +tests/test_config.py +tests/test_helpers.py +tests/test_instance_config.py +tests/test_json_tag.py +tests/test_logging.py +tests/test_regression.py +tests/test_reqctx.py +tests/test_signals.py +tests/test_subclassing.py +tests/test_templating.py +tests/test_testing.py +tests/test_user_error_handler.py +tests/test_views.py +tests/static/config.json +tests/static/index.html +tests/templates/_macro.html +tests/templates/context_template.html +tests/templates/escaping_template.html +tests/templates/mail.txt +tests/templates/non_escaping_template.txt +tests/templates/simple_template.html +tests/templates/template_filter.html +tests/templates/template_test.html +tests/templates/nested/nested.txt +tests/test_apps/.env +tests/test_apps/.flaskenv +tests/test_apps/blueprintapp/__init__.py +tests/test_apps/blueprintapp/apps/__init__.py +tests/test_apps/blueprintapp/apps/admin/__init__.py +tests/test_apps/blueprintapp/apps/admin/static/test.txt +tests/test_apps/blueprintapp/apps/admin/static/css/test.css +tests/test_apps/blueprintapp/apps/admin/templates/admin/index.html +tests/test_apps/blueprintapp/apps/frontend/__init__.py +tests/test_apps/blueprintapp/apps/frontend/templates/frontend/index.html +tests/test_apps/cliapp/__init__.py +tests/test_apps/cliapp/app.py +tests/test_apps/cliapp/factory.py +tests/test_apps/cliapp/importerrorapp.py +tests/test_apps/cliapp/message.txt +tests/test_apps/cliapp/multiapp.py +tests/test_apps/cliapp/inner1/__init__.py +tests/test_apps/cliapp/inner1/inner2/__init__.py +tests/test_apps/cliapp/inner1/inner2/flask.py +tests/test_apps/helloworld/hello.py +tests/test_apps/helloworld/wsgi.py +tests/test_apps/subdomaintestmodule/__init__.py +tests/test_apps/subdomaintestmodule/static/hello.txt \ No newline at end of file diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/dependency_links.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/entry_points.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/entry_points.txt new file mode 100644 index 00000000000000..1eb025200e62eb --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/entry_points.txt @@ -0,0 +1,3 @@ +[console_scripts] +flask = flask.cli:main + diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/installed-files.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..150041120d31e5 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/installed-files.txt @@ -0,0 +1,48 @@ +../flask/testing.py +../flask/templating.py +../flask/__main__.py +../flask/sessions.py +../flask/signals.py +../flask/helpers.py +../flask/debughelpers.py +../flask/wrappers.py +../flask/app.py +../flask/ctx.py +../flask/config.py +../flask/logging.py +../flask/blueprints.py +../flask/views.py +../flask/cli.py +../flask/_compat.py +../flask/globals.py +../flask/__init__.py +../flask/json/tag.py +../flask/json/__init__.py +../flask/testing.pyc +../flask/templating.pyc +../flask/__main__.pyc +../flask/sessions.pyc +../flask/signals.pyc +../flask/helpers.pyc +../flask/debughelpers.pyc +../flask/wrappers.pyc +../flask/app.pyc +../flask/ctx.pyc +../flask/config.pyc +../flask/logging.pyc +../flask/blueprints.pyc +../flask/views.pyc +../flask/cli.pyc +../flask/_compat.pyc +../flask/globals.pyc +../flask/__init__.pyc +../flask/json/tag.pyc +../flask/json/__init__.pyc +not-zip-safe +entry_points.txt +dependency_links.txt +PKG-INFO +top_level.txt +requires.txt +SOURCES.txt +../../../../bin/flask diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/not-zip-safe b/pyextra/Flask-1.0.2-py2.7.egg-info/not-zip-safe new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/not-zip-safe @@ -0,0 +1 @@ + diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/requires.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/requires.txt new file mode 100644 index 00000000000000..f51579ea91ca2e --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/requires.txt @@ -0,0 +1,20 @@ +Werkzeug>=0.14 +Jinja2>=2.10 +itsdangerous>=0.24 +click>=5.1 + +[dev] +pytest>=3 +coverage +tox +sphinx +pallets-sphinx-themes +sphinxcontrib-log-cabinet + +[docs] +sphinx +pallets-sphinx-themes +sphinxcontrib-log-cabinet + +[dotenv] +python-dotenv diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/top_level.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..7e1060246fd674 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +flask diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/PKG-INFO b/pyextra/Jinja2-2.10-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..b4398d64900217 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/PKG-INFO @@ -0,0 +1,62 @@ +Metadata-Version: 1.1 +Name: Jinja2 +Version: 2.10 +Summary: A small but fast and easy to use stand-alone template engine written in pure python. +Home-page: http://jinja.pocoo.org/ +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: BSD +Description: + Jinja2 + ~~~~~~ + + Jinja2 is a template engine written in pure Python. It provides a + `Django`_ inspired non-XML syntax but supports inline expressions and + an optional `sandboxed`_ environment. + + Nutshell + -------- + + Here a small example of a Jinja template:: + + {% extends 'base.html' %} + {% block title %}Memberlist{% endblock %} + {% block content %} + + {% endblock %} + + Philosophy + ---------- + + Application logic is for the controller but don't try to make the life + for the template designer too hard by giving him too few functionality. + + For more informations visit the new `Jinja2 webpage`_ and `documentation`_. + + .. _sandboxed: https://en.wikipedia.org/wiki/Sandbox_(computer_security) + .. _Django: https://www.djangoproject.com/ + .. _Jinja2 webpage: http://jinja.pocoo.org/ + .. _documentation: http://jinja.pocoo.org/2/documentation/ + +Platform: UNKNOWN +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 2 +Classifier: Programming Language :: Python :: 2.6 +Classifier: Programming Language :: Python :: 2.7 +Classifier: Programming Language :: Python :: 3 +Classifier: Programming Language :: Python :: 3.3 +Classifier: Programming Language :: Python :: 3.4 +Classifier: Programming Language :: Python :: 3.5 +Classifier: Programming Language :: Python :: 3.6 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Software Development :: Libraries :: Python Modules +Classifier: Topic :: Text Processing :: Markup :: HTML diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/SOURCES.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..93158e1f63bcee --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,133 @@ +AUTHORS +CHANGES.rst +LICENSE +MANIFEST.in +README.rst +setup.cfg +setup.py +Jinja2.egg-info/PKG-INFO +Jinja2.egg-info/SOURCES.txt +Jinja2.egg-info/dependency_links.txt +Jinja2.egg-info/entry_points.txt +Jinja2.egg-info/not-zip-safe +Jinja2.egg-info/requires.txt +Jinja2.egg-info/top_level.txt +artwork/jinjalogo.svg +docs/Makefile +docs/api.rst +docs/cache_extension.py +docs/changelog.rst +docs/conf.py +docs/contents.rst.inc +docs/extensions.rst +docs/faq.rst +docs/index.rst +docs/integration.rst +docs/intro.rst +docs/jinjaext.py +docs/jinjastyle.sty +docs/latexindex.rst +docs/logo.pdf +docs/nativetypes.rst +docs/sandbox.rst +docs/switching.rst +docs/templates.rst +docs/tricks.rst +docs/_static/.ignore +docs/_static/jinja-small.png +docs/_templates/sidebarintro.html +docs/_templates/sidebarlogo.html +docs/_themes/LICENSE +docs/_themes/README +docs/_themes/jinja/layout.html +docs/_themes/jinja/relations.html +docs/_themes/jinja/theme.conf +docs/_themes/jinja/static/jinja.css_t +examples/bench.py +examples/profile.py +examples/basic/cycle.py +examples/basic/debugger.py +examples/basic/inheritance.py +examples/basic/test.py +examples/basic/test_filter_and_linestatements.py +examples/basic/test_loop_filter.py +examples/basic/translate.py +examples/basic/templates/broken.html +examples/basic/templates/subbroken.html +examples/rwbench/djangoext.py +examples/rwbench/rwbench.py +examples/rwbench/django/_form.html +examples/rwbench/django/_input_field.html +examples/rwbench/django/_textarea.html +examples/rwbench/django/index.html +examples/rwbench/django/layout.html +examples/rwbench/genshi/helpers.html +examples/rwbench/genshi/index.html +examples/rwbench/genshi/layout.html +examples/rwbench/jinja/helpers.html +examples/rwbench/jinja/index.html +examples/rwbench/jinja/layout.html +examples/rwbench/mako/helpers.html +examples/rwbench/mako/index.html +examples/rwbench/mako/layout.html +ext/djangojinja2.py +ext/inlinegettext.py +ext/jinja.el +ext/Vim/jinja.vim +ext/django2jinja/django2jinja.py +ext/django2jinja/example.py +ext/django2jinja/templates/index.html +ext/django2jinja/templates/layout.html +ext/django2jinja/templates/subtemplate.html +jinja2/__init__.py +jinja2/_compat.py +jinja2/_identifier.py +jinja2/asyncfilters.py +jinja2/asyncsupport.py +jinja2/bccache.py +jinja2/compiler.py +jinja2/constants.py +jinja2/debug.py +jinja2/defaults.py +jinja2/environment.py +jinja2/exceptions.py +jinja2/ext.py +jinja2/filters.py +jinja2/idtracking.py +jinja2/lexer.py +jinja2/loaders.py +jinja2/meta.py +jinja2/nativetypes.py +jinja2/nodes.py +jinja2/optimizer.py +jinja2/parser.py +jinja2/runtime.py +jinja2/sandbox.py +jinja2/tests.py +jinja2/utils.py +jinja2/visitor.py +tests/conftest.py +tests/test_api.py +tests/test_async.py +tests/test_asyncfilters.py +tests/test_bytecode_cache.py +tests/test_core_tags.py +tests/test_debug.py +tests/test_ext.py +tests/test_features.py +tests/test_filters.py +tests/test_idtracking.py +tests/test_imports.py +tests/test_inheritance.py +tests/test_lexnparse.py +tests/test_loader.py +tests/test_nativetypes.py +tests/test_regression.py +tests/test_security.py +tests/test_tests.py +tests/test_utils.py +tests/res/__init__.py +tests/res/templates/broken.html +tests/res/templates/syntaxerror.html +tests/res/templates/test.html +tests/res/templates/foo/test.html \ No newline at end of file diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/dependency_links.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/entry_points.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/entry_points.txt new file mode 100644 index 00000000000000..32e6b753028430 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/entry_points.txt @@ -0,0 +1,4 @@ + + [babel.extractors] + jinja2 = jinja2.ext:babel_extract[i18n] + \ No newline at end of file diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/installed-files.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..c2af213acef197 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/installed-files.txt @@ -0,0 +1,61 @@ +../jinja2/lexer.py +../jinja2/idtracking.py +../jinja2/_identifier.py +../jinja2/nodes.py +../jinja2/asyncfilters.py +../jinja2/loaders.py +../jinja2/defaults.py +../jinja2/meta.py +../jinja2/compiler.py +../jinja2/environment.py +../jinja2/tests.py +../jinja2/sandbox.py +../jinja2/filters.py +../jinja2/exceptions.py +../jinja2/asyncsupport.py +../jinja2/visitor.py +../jinja2/constants.py +../jinja2/utils.py +../jinja2/ext.py +../jinja2/optimizer.py +../jinja2/nativetypes.py +../jinja2/parser.py +../jinja2/runtime.py +../jinja2/debug.py +../jinja2/_compat.py +../jinja2/bccache.py +../jinja2/__init__.py +../jinja2/lexer.pyc +../jinja2/idtracking.pyc +../jinja2/_identifier.pyc +../jinja2/nodes.pyc +../jinja2/asyncfilters.pyc +../jinja2/loaders.pyc +../jinja2/defaults.pyc +../jinja2/meta.pyc +../jinja2/compiler.pyc +../jinja2/environment.pyc +../jinja2/tests.pyc +../jinja2/sandbox.pyc +../jinja2/filters.pyc +../jinja2/exceptions.pyc +../jinja2/asyncsupport.pyc +../jinja2/visitor.pyc +../jinja2/constants.pyc +../jinja2/utils.pyc +../jinja2/ext.pyc +../jinja2/optimizer.pyc +../jinja2/nativetypes.pyc +../jinja2/parser.pyc +../jinja2/runtime.pyc +../jinja2/debug.pyc +../jinja2/_compat.pyc +../jinja2/bccache.pyc +../jinja2/__init__.pyc +not-zip-safe +entry_points.txt +dependency_links.txt +PKG-INFO +top_level.txt +requires.txt +SOURCES.txt diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/not-zip-safe b/pyextra/Jinja2-2.10-py2.7.egg-info/not-zip-safe new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/not-zip-safe @@ -0,0 +1 @@ + diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/requires.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/requires.txt new file mode 100644 index 00000000000000..1d74a32c66fb4b --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/requires.txt @@ -0,0 +1,4 @@ +MarkupSafe>=0.23 + +[i18n] +Babel>=0.8 diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/top_level.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..7f7afbf3bf54b3 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +jinja2 diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/PKG-INFO b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..a0a627684d17d0 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/PKG-INFO @@ -0,0 +1,104 @@ +Metadata-Version: 1.1 +Name: Werkzeug +Version: 0.14.1 +Summary: The comprehensive WSGI web application library. +Home-page: https://www.palletsprojects.org/p/werkzeug/ +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: BSD +Description: Werkzeug + ======== + + Werkzeug is a comprehensive `WSGI`_ web application library. It began as + a simple collection of various utilities for WSGI applications and has + become one of the most advanced WSGI utility libraries. + + It includes: + + * An interactive debugger that allows inspecting stack traces and source + code in the browser with an interactive interpreter for any frame in + the stack. + * A full-featured request object with objects to interact with headers, + query args, form data, files, and cookies. + * A response object that can wrap other WSGI applications and handle + streaming data. + * A routing system for matching URLs to endpoints and generating URLs + for endpoints, with an extensible system for capturing variables from + URLs. + * HTTP utilities to handle entity tags, cache control, dates, user + agents, cookies, files, and more. + * A threaded WSGI server for use while developing applications locally. + * A test client for simulating HTTP requests during testing without + requiring running a server. + + Werkzeug is Unicode aware and doesn't enforce any dependencies. It is up + to the developer to choose a template engine, database adapter, and even + how to handle requests. It can be used to build all sorts of end user + applications such as blogs, wikis, or bulletin boards. + + `Flask`_ wraps Werkzeug, using it to handle the details of WSGI while + providing more structure and patterns for defining powerful + applications. + + + Installing + ---------- + + Install and update using `pip`_: + + .. code-block:: text + + pip install -U Werkzeug + + + A Simple Example + ---------------- + + .. code-block:: python + + from werkzeug.wrappers import Request, Response + + @Request.application + def application(request): + return Response('Hello, World!') + + if __name__ == '__main__': + from werkzeug.serving import run_simple + run_simple('localhost', 4000, application) + + + Links + ----- + + * Website: https://www.palletsprojects.com/p/werkzeug/ + * Releases: https://pypi.org/project/Werkzeug/ + * Code: https://github.com/pallets/werkzeug + * Issue tracker: https://github.com/pallets/werkzeug/issues + * Test status: + + * Linux, Mac: https://travis-ci.org/pallets/werkzeug + * Windows: https://ci.appveyor.com/project/davidism/werkzeug + + * Test coverage: https://codecov.io/gh/pallets/werkzeug + + .. _WSGI: https://wsgi.readthedocs.io/en/latest/ + .. _Flask: https://www.palletsprojects.com/p/flask/ + .. _pip: https://pip.pypa.io/en/stable/quickstart/ + +Platform: any +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 2 +Classifier: Programming Language :: Python :: 2.6 +Classifier: Programming Language :: Python :: 2.7 +Classifier: Programming Language :: Python :: 3 +Classifier: Programming Language :: Python :: 3.3 +Classifier: Programming Language :: Python :: 3.4 +Classifier: Programming Language :: Python :: 3.5 +Classifier: Programming Language :: Python :: 3.6 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Software Development :: Libraries :: Python Modules diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/SOURCES.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..9d3b7690895811 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,299 @@ +AUTHORS +CHANGES.rst +LICENSE +MANIFEST.in +Makefile +README.rst +setup.cfg +setup.py +tox.ini +Werkzeug.egg-info/PKG-INFO +Werkzeug.egg-info/SOURCES.txt +Werkzeug.egg-info/dependency_links.txt +Werkzeug.egg-info/not-zip-safe +Werkzeug.egg-info/requires.txt +Werkzeug.egg-info/top_level.txt +artwork/.DS_Store +artwork/logo.png +artwork/logo.svg +docs/.DS_Store +docs/Makefile +docs/changes.rst +docs/conf.py +docs/contents.rst.inc +docs/datastructures.rst +docs/debug.rst +docs/exceptions.rst +docs/filesystem.rst +docs/http.rst +docs/index.rst +docs/installation.rst +docs/latexindex.rst +docs/levels.rst +docs/local.rst +docs/logo.pdf +docs/make.bat +docs/makearchive.py +docs/middlewares.rst +docs/python3.rst +docs/quickstart.rst +docs/request_data.rst +docs/routing.rst +docs/serving.rst +docs/terms.rst +docs/test.rst +docs/transition.rst +docs/tutorial.rst +docs/unicode.rst +docs/urls.rst +docs/utils.rst +docs/werkzeugext.py +docs/werkzeugstyle.sty +docs/wrappers.rst +docs/wsgi.rst +docs/_static/background.png +docs/_static/codebackground.png +docs/_static/contents.png +docs/_static/debug-screenshot.png +docs/_static/favicon.ico +docs/_static/header.png +docs/_static/navigation.png +docs/_static/navigation_active.png +docs/_static/shortly.png +docs/_static/shorty-screenshot.png +docs/_static/style.css +docs/_static/werkzeug.js +docs/_static/werkzeug.png +docs/_templates/sidebarintro.html +docs/_templates/sidebarlogo.html +docs/contrib/atom.rst +docs/contrib/cache.rst +docs/contrib/fixers.rst +docs/contrib/index.rst +docs/contrib/iterio.rst +docs/contrib/lint.rst +docs/contrib/profiler.rst +docs/contrib/securecookie.rst +docs/contrib/sessions.rst +docs/contrib/wrappers.rst +docs/deployment/cgi.rst +docs/deployment/fastcgi.rst +docs/deployment/index.rst +docs/deployment/mod_wsgi.rst +docs/deployment/proxying.rst +examples/README +examples/cookieauth.py +examples/httpbasicauth.py +examples/manage-coolmagic.py +examples/manage-couchy.py +examples/manage-cupoftee.py +examples/manage-i18nurls.py +examples/manage-plnt.py +examples/manage-shorty.py +examples/manage-simplewiki.py +examples/manage-webpylike.py +examples/upload.py +examples/contrib/README +examples/contrib/securecookie.py +examples/contrib/sessions.py +examples/coolmagic/__init__.py +examples/coolmagic/application.py +examples/coolmagic/helpers.py +examples/coolmagic/utils.py +examples/coolmagic/public/style.css +examples/coolmagic/templates/layout.html +examples/coolmagic/templates/static/about.html +examples/coolmagic/templates/static/index.html +examples/coolmagic/templates/static/not_found.html +examples/coolmagic/views/__init__.py +examples/coolmagic/views/static.py +examples/couchy/README +examples/couchy/__init__.py +examples/couchy/application.py +examples/couchy/models.py +examples/couchy/utils.py +examples/couchy/views.py +examples/couchy/static/style.css +examples/couchy/templates/display.html +examples/couchy/templates/layout.html +examples/couchy/templates/list.html +examples/couchy/templates/new.html +examples/couchy/templates/not_found.html +examples/cupoftee/__init__.py +examples/cupoftee/application.py +examples/cupoftee/db.py +examples/cupoftee/network.py +examples/cupoftee/pages.py +examples/cupoftee/utils.py +examples/cupoftee/shared/content.png +examples/cupoftee/shared/down.png +examples/cupoftee/shared/favicon.ico +examples/cupoftee/shared/header.png +examples/cupoftee/shared/logo.png +examples/cupoftee/shared/style.css +examples/cupoftee/shared/up.png +examples/cupoftee/templates/layout.html +examples/cupoftee/templates/missingpage.html +examples/cupoftee/templates/search.html +examples/cupoftee/templates/server.html +examples/cupoftee/templates/serverlist.html +examples/i18nurls/__init__.py +examples/i18nurls/application.py +examples/i18nurls/urls.py +examples/i18nurls/views.py +examples/i18nurls/templates/about.html +examples/i18nurls/templates/blog.html +examples/i18nurls/templates/index.html +examples/i18nurls/templates/layout.html +examples/partial/README +examples/partial/complex_routing.py +examples/plnt/__init__.py +examples/plnt/database.py +examples/plnt/sync.py +examples/plnt/utils.py +examples/plnt/views.py +examples/plnt/webapp.py +examples/plnt/shared/style.css +examples/plnt/templates/about.html +examples/plnt/templates/index.html +examples/plnt/templates/layout.html +examples/shortly/shortly.py +examples/shortly/static/style.css +examples/shortly/templates/404.html +examples/shortly/templates/layout.html +examples/shortly/templates/new_url.html +examples/shortly/templates/short_link_details.html +examples/shorty/__init__.py +examples/shorty/application.py +examples/shorty/models.py +examples/shorty/utils.py +examples/shorty/views.py +examples/shorty/static/style.css +examples/shorty/templates/display.html +examples/shorty/templates/layout.html +examples/shorty/templates/list.html +examples/shorty/templates/new.html +examples/shorty/templates/not_found.html +examples/simplewiki/__init__.py +examples/simplewiki/actions.py +examples/simplewiki/application.py +examples/simplewiki/database.py +examples/simplewiki/specialpages.py +examples/simplewiki/utils.py +examples/simplewiki/shared/style.css +examples/simplewiki/templates/action_diff.html +examples/simplewiki/templates/action_edit.html +examples/simplewiki/templates/action_log.html +examples/simplewiki/templates/action_revert.html +examples/simplewiki/templates/action_show.html +examples/simplewiki/templates/layout.html +examples/simplewiki/templates/macros.xml +examples/simplewiki/templates/missing_action.html +examples/simplewiki/templates/page_index.html +examples/simplewiki/templates/page_missing.html +examples/simplewiki/templates/recent_changes.html +examples/webpylike/example.py +examples/webpylike/webpylike.py +tests/__init__.py +tests/conftest.py +tests/test_compat.py +tests/test_datastructures.py +tests/test_debug.py +tests/test_exceptions.py +tests/test_formparser.py +tests/test_http.py +tests/test_internal.py +tests/test_local.py +tests/test_routing.py +tests/test_security.py +tests/test_serving.py +tests/test_test.py +tests/test_urls.py +tests/test_utils.py +tests/test_wrappers.py +tests/test_wsgi.py +tests/contrib/__init__.py +tests/contrib/test_atom.py +tests/contrib/test_cache.py +tests/contrib/test_fixers.py +tests/contrib/test_iterio.py +tests/contrib/test_securecookie.py +tests/contrib/test_sessions.py +tests/contrib/test_wrappers.py +tests/contrib/cache/conftest.py +tests/contrib/cache/test_cache.py +tests/hypothesis/__init__.py +tests/hypothesis/test_urls.py +tests/multipart/__init__.py +tests/multipart/ie7_full_path_request.txt +tests/multipart/test_collect.py +tests/multipart/firefox3-2png1txt/file1.png +tests/multipart/firefox3-2png1txt/file2.png +tests/multipart/firefox3-2png1txt/request.txt +tests/multipart/firefox3-2png1txt/text.txt +tests/multipart/firefox3-2pnglongtext/file1.png +tests/multipart/firefox3-2pnglongtext/file2.png +tests/multipart/firefox3-2pnglongtext/request.txt +tests/multipart/firefox3-2pnglongtext/text.txt +tests/multipart/ie6-2png1txt/file1.png +tests/multipart/ie6-2png1txt/file2.png +tests/multipart/ie6-2png1txt/request.txt +tests/multipart/ie6-2png1txt/text.txt +tests/multipart/opera8-2png1txt/file1.png +tests/multipart/opera8-2png1txt/file2.png +tests/multipart/opera8-2png1txt/request.txt +tests/multipart/opera8-2png1txt/text.txt +tests/multipart/webkit3-2png1txt/file1.png +tests/multipart/webkit3-2png1txt/file2.png +tests/multipart/webkit3-2png1txt/request.txt +tests/multipart/webkit3-2png1txt/text.txt +tests/res/chunked.txt +tests/res/test.txt +werkzeug/__init__.py +werkzeug/_compat.py +werkzeug/_internal.py +werkzeug/_reloader.py +werkzeug/datastructures.py +werkzeug/exceptions.py +werkzeug/filesystem.py +werkzeug/formparser.py +werkzeug/http.py +werkzeug/local.py +werkzeug/posixemulation.py +werkzeug/routing.py +werkzeug/security.py +werkzeug/serving.py +werkzeug/test.py +werkzeug/testapp.py +werkzeug/urls.py +werkzeug/useragents.py +werkzeug/utils.py +werkzeug/websocket.py +werkzeug/wrappers.py +werkzeug/wsgi.py +werkzeug/contrib/__init__.py +werkzeug/contrib/atom.py +werkzeug/contrib/cache.py +werkzeug/contrib/fixers.py +werkzeug/contrib/iterio.py +werkzeug/contrib/jsrouting.py +werkzeug/contrib/limiter.py +werkzeug/contrib/lint.py +werkzeug/contrib/profiler.py +werkzeug/contrib/securecookie.py +werkzeug/contrib/sessions.py +werkzeug/contrib/testtools.py +werkzeug/contrib/wrappers.py +werkzeug/debug/__init__.py +werkzeug/debug/console.py +werkzeug/debug/repr.py +werkzeug/debug/tbtools.py +werkzeug/debug/shared/FONT_LICENSE +werkzeug/debug/shared/console.png +werkzeug/debug/shared/debugger.js +werkzeug/debug/shared/jquery.js +werkzeug/debug/shared/less.png +werkzeug/debug/shared/more.png +werkzeug/debug/shared/source.png +werkzeug/debug/shared/style.css +werkzeug/debug/shared/ubuntu.ttf \ No newline at end of file diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/dependency_links.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/installed-files.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..105fb3c0b60939 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/installed-files.txt @@ -0,0 +1,93 @@ +../werkzeug/_reloader.py +../werkzeug/_internal.py +../werkzeug/serving.py +../werkzeug/local.py +../werkzeug/filesystem.py +../werkzeug/security.py +../werkzeug/__init__.py +../werkzeug/test.py +../werkzeug/formparser.py +../werkzeug/posixemulation.py +../werkzeug/utils.py +../werkzeug/wrappers.py +../werkzeug/routing.py +../werkzeug/http.py +../werkzeug/useragents.py +../werkzeug/exceptions.py +../werkzeug/_compat.py +../werkzeug/datastructures.py +../werkzeug/urls.py +../werkzeug/websocket.py +../werkzeug/wsgi.py +../werkzeug/testapp.py +../werkzeug/contrib/sessions.py +../werkzeug/contrib/cache.py +../werkzeug/contrib/__init__.py +../werkzeug/contrib/testtools.py +../werkzeug/contrib/wrappers.py +../werkzeug/contrib/jsrouting.py +../werkzeug/contrib/fixers.py +../werkzeug/contrib/profiler.py +../werkzeug/contrib/iterio.py +../werkzeug/contrib/atom.py +../werkzeug/contrib/securecookie.py +../werkzeug/contrib/limiter.py +../werkzeug/contrib/lint.py +../werkzeug/debug/console.py +../werkzeug/debug/tbtools.py +../werkzeug/debug/__init__.py +../werkzeug/debug/repr.py +../werkzeug/debug/shared/FONT_LICENSE +../werkzeug/debug/shared/console.png +../werkzeug/debug/shared/debugger.js +../werkzeug/debug/shared/jquery.js +../werkzeug/debug/shared/less.png +../werkzeug/debug/shared/more.png +../werkzeug/debug/shared/source.png +../werkzeug/debug/shared/style.css +../werkzeug/debug/shared/ubuntu.ttf +../werkzeug/_reloader.pyc +../werkzeug/_internal.pyc +../werkzeug/serving.pyc +../werkzeug/local.pyc +../werkzeug/filesystem.pyc +../werkzeug/security.pyc +../werkzeug/__init__.pyc +../werkzeug/test.pyc +../werkzeug/formparser.pyc +../werkzeug/posixemulation.pyc +../werkzeug/utils.pyc +../werkzeug/wrappers.pyc +../werkzeug/routing.pyc +../werkzeug/http.pyc +../werkzeug/useragents.pyc +../werkzeug/exceptions.pyc +../werkzeug/_compat.pyc +../werkzeug/datastructures.pyc +../werkzeug/urls.pyc +../werkzeug/websocket.pyc +../werkzeug/wsgi.pyc +../werkzeug/testapp.pyc +../werkzeug/contrib/sessions.pyc +../werkzeug/contrib/cache.pyc +../werkzeug/contrib/__init__.pyc +../werkzeug/contrib/testtools.pyc +../werkzeug/contrib/wrappers.pyc +../werkzeug/contrib/jsrouting.pyc +../werkzeug/contrib/fixers.pyc +../werkzeug/contrib/profiler.pyc +../werkzeug/contrib/iterio.pyc +../werkzeug/contrib/atom.pyc +../werkzeug/contrib/securecookie.pyc +../werkzeug/contrib/limiter.pyc +../werkzeug/contrib/lint.pyc +../werkzeug/debug/console.pyc +../werkzeug/debug/tbtools.pyc +../werkzeug/debug/__init__.pyc +../werkzeug/debug/repr.pyc +PKG-INFO +not-zip-safe +SOURCES.txt +requires.txt +top_level.txt +dependency_links.txt diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/not-zip-safe b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/not-zip-safe new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/not-zip-safe @@ -0,0 +1 @@ + diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/requires.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/requires.txt new file mode 100644 index 00000000000000..dd8c7c51f12455 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/requires.txt @@ -0,0 +1,12 @@ + +[dev] +pytest +coverage +tox +sphinx + +[termcolor] +termcolor + +[watchdog] +watchdog diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/top_level.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..6fe8da8499399d --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +werkzeug diff --git a/pyextra/bin/flask b/pyextra/bin/flask new file mode 100755 index 00000000000000..2adb78c4a57b77 --- /dev/null +++ b/pyextra/bin/flask @@ -0,0 +1,10 @@ +#!/usr/local/bin/python +# EASY-INSTALL-ENTRY-SCRIPT: 'Flask==1.0.2','console_scripts','flask' +__requires__ = 'Flask==1.0.2' +import sys +from pkg_resources import load_entry_point + +if __name__ == '__main__': + sys.exit( + load_entry_point('Flask==1.0.2', 'console_scripts', 'flask')() + ) diff --git a/pyextra/click-6.7-py2.7.egg-info/PKG-INFO b/pyextra/click-6.7-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..bbb17b38331c58 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/PKG-INFO @@ -0,0 +1,13 @@ +Metadata-Version: 1.1 +Name: click +Version: 6.7 +Summary: A simple wrapper around optparse for powerful command line utilities. +Home-page: http://github.com/mitsuhiko/click +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: UNKNOWN +Description: UNKNOWN +Platform: UNKNOWN +Classifier: License :: OSI Approved :: BSD License +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 3 diff --git a/pyextra/click-6.7-py2.7.egg-info/SOURCES.txt b/pyextra/click-6.7-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..5eed4349ef6793 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,114 @@ +CHANGES +LICENSE +MANIFEST.in +Makefile +README +setup.cfg +setup.py +artwork/logo.svg +click/__init__.py +click/_bashcomplete.py +click/_compat.py +click/_termui_impl.py +click/_textwrap.py +click/_unicodefun.py +click/_winconsole.py +click/core.py +click/decorators.py +click/exceptions.py +click/formatting.py +click/globals.py +click/parser.py +click/termui.py +click/testing.py +click/types.py +click/utils.py +click.egg-info/PKG-INFO +click.egg-info/SOURCES.txt +click.egg-info/dependency_links.txt +click.egg-info/top_level.txt +docs/Makefile +docs/advanced.rst +docs/api.rst +docs/arguments.rst +docs/bashcomplete.rst +docs/changelog.rst +docs/clickdoctools.py +docs/commands.rst +docs/complex.rst +docs/conf.py +docs/contrib.rst +docs/documentation.rst +docs/exceptions.rst +docs/index.rst +docs/license.rst +docs/make.bat +docs/options.rst +docs/parameters.rst +docs/prompts.rst +docs/python3.rst +docs/quickstart.rst +docs/setuptools.rst +docs/testing.rst +docs/upgrading.rst +docs/utils.rst +docs/why.rst +docs/wincmd.rst +docs/_static/click-small.png +docs/_static/click-small@2x.png +docs/_static/click.png +docs/_static/click@2x.png +docs/_templates/sidebarintro.html +docs/_templates/sidebarlogo.html +examples/README +examples/aliases/README +examples/aliases/aliases.ini +examples/aliases/aliases.py +examples/aliases/setup.py +examples/colors/README +examples/colors/colors.py +examples/colors/setup.py +examples/complex/README +examples/complex/setup.py +examples/complex/complex/__init__.py +examples/complex/complex/cli.py +examples/complex/complex/commands/__init__.py +examples/complex/complex/commands/cmd_init.py +examples/complex/complex/commands/cmd_status.py +examples/imagepipe/.gitignore +examples/imagepipe/README +examples/imagepipe/example01.jpg +examples/imagepipe/example02.jpg +examples/imagepipe/imagepipe.py +examples/imagepipe/setup.py +examples/inout/README +examples/inout/inout.py +examples/inout/setup.py +examples/naval/README +examples/naval/naval.py +examples/naval/setup.py +examples/repo/README +examples/repo/repo.py +examples/repo/setup.py +examples/termui/README +examples/termui/setup.py +examples/termui/termui.py +examples/validation/README +examples/validation/setup.py +examples/validation/validation.py +tests/conftest.py +tests/test_arguments.py +tests/test_bashcomplete.py +tests/test_basic.py +tests/test_chain.py +tests/test_commands.py +tests/test_compat.py +tests/test_context.py +tests/test_defaults.py +tests/test_formatting.py +tests/test_imports.py +tests/test_normalization.py +tests/test_options.py +tests/test_termui.py +tests/test_testing.py +tests/test_utils.py \ No newline at end of file diff --git a/pyextra/click-6.7-py2.7.egg-info/dependency_links.txt b/pyextra/click-6.7-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/click-6.7-py2.7.egg-info/installed-files.txt b/pyextra/click-6.7-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..63d1b52c135353 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/installed-files.txt @@ -0,0 +1,38 @@ +../click/exceptions.py +../click/testing.py +../click/decorators.py +../click/parser.py +../click/formatting.py +../click/globals.py +../click/_termui_impl.py +../click/__init__.py +../click/_compat.py +../click/_winconsole.py +../click/_unicodefun.py +../click/_textwrap.py +../click/_bashcomplete.py +../click/core.py +../click/types.py +../click/termui.py +../click/utils.py +../click/exceptions.pyc +../click/testing.pyc +../click/decorators.pyc +../click/parser.pyc +../click/formatting.pyc +../click/globals.pyc +../click/_termui_impl.pyc +../click/__init__.pyc +../click/_compat.pyc +../click/_winconsole.pyc +../click/_unicodefun.pyc +../click/_textwrap.pyc +../click/_bashcomplete.pyc +../click/core.pyc +../click/types.pyc +../click/termui.pyc +../click/utils.pyc +SOURCES.txt +top_level.txt +PKG-INFO +dependency_links.txt diff --git a/pyextra/click-6.7-py2.7.egg-info/top_level.txt b/pyextra/click-6.7-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..dca9a909647e3b --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +click diff --git a/pyextra/click/__init__.py b/pyextra/click/__init__.py new file mode 100644 index 00000000000000..971e55d0a8c6de --- /dev/null +++ b/pyextra/click/__init__.py @@ -0,0 +1,98 @@ +# -*- coding: utf-8 -*- +""" + click + ~~~~~ + + Click is a simple Python module that wraps the stdlib's optparse to make + writing command line scripts fun. Unlike other modules, it's based around + a simple API that does not come with too much magic and is composable. + + In case optparse ever gets removed from the stdlib, it will be shipped by + this module. + + :copyright: (c) 2014 by Armin Ronacher. + :license: BSD, see LICENSE for more details. +""" + +# Core classes +from .core import Context, BaseCommand, Command, MultiCommand, Group, \ + CommandCollection, Parameter, Option, Argument + +# Globals +from .globals import get_current_context + +# Decorators +from .decorators import pass_context, pass_obj, make_pass_decorator, \ + command, group, argument, option, confirmation_option, \ + password_option, version_option, help_option + +# Types +from .types import ParamType, File, Path, Choice, IntRange, Tuple, \ + STRING, INT, FLOAT, BOOL, UUID, UNPROCESSED + +# Utilities +from .utils import echo, get_binary_stream, get_text_stream, open_file, \ + format_filename, get_app_dir, get_os_args + +# Terminal functions +from .termui import prompt, confirm, get_terminal_size, echo_via_pager, \ + progressbar, clear, style, unstyle, secho, edit, launch, getchar, \ + pause + +# Exceptions +from .exceptions import ClickException, UsageError, BadParameter, \ + FileError, Abort, NoSuchOption, BadOptionUsage, BadArgumentUsage, \ + MissingParameter + +# Formatting +from .formatting import HelpFormatter, wrap_text + +# Parsing +from .parser import OptionParser + + +__all__ = [ + # Core classes + 'Context', 'BaseCommand', 'Command', 'MultiCommand', 'Group', + 'CommandCollection', 'Parameter', 'Option', 'Argument', + + # Globals + 'get_current_context', + + # Decorators + 'pass_context', 'pass_obj', 'make_pass_decorator', 'command', 'group', + 'argument', 'option', 'confirmation_option', 'password_option', + 'version_option', 'help_option', + + # Types + 'ParamType', 'File', 'Path', 'Choice', 'IntRange', 'Tuple', 'STRING', + 'INT', 'FLOAT', 'BOOL', 'UUID', 'UNPROCESSED', + + # Utilities + 'echo', 'get_binary_stream', 'get_text_stream', 'open_file', + 'format_filename', 'get_app_dir', 'get_os_args', + + # Terminal functions + 'prompt', 'confirm', 'get_terminal_size', 'echo_via_pager', + 'progressbar', 'clear', 'style', 'unstyle', 'secho', 'edit', 'launch', + 'getchar', 'pause', + + # Exceptions + 'ClickException', 'UsageError', 'BadParameter', 'FileError', + 'Abort', 'NoSuchOption', 'BadOptionUsage', 'BadArgumentUsage', + 'MissingParameter', + + # Formatting + 'HelpFormatter', 'wrap_text', + + # Parsing + 'OptionParser', +] + + +# Controls if click should emit the warning about the use of unicode +# literals. +disable_unicode_literals_warning = False + + +__version__ = '6.7' diff --git a/pyextra/click/_bashcomplete.py b/pyextra/click/_bashcomplete.py new file mode 100644 index 00000000000000..d9d26d28b053de --- /dev/null +++ b/pyextra/click/_bashcomplete.py @@ -0,0 +1,83 @@ +import os +import re +from .utils import echo +from .parser import split_arg_string +from .core import MultiCommand, Option + + +COMPLETION_SCRIPT = ''' +%(complete_func)s() { + COMPREPLY=( $( env COMP_WORDS="${COMP_WORDS[*]}" \\ + COMP_CWORD=$COMP_CWORD \\ + %(autocomplete_var)s=complete $1 ) ) + return 0 +} + +complete -F %(complete_func)s -o default %(script_names)s +''' + +_invalid_ident_char_re = re.compile(r'[^a-zA-Z0-9_]') + + +def get_completion_script(prog_name, complete_var): + cf_name = _invalid_ident_char_re.sub('', prog_name.replace('-', '_')) + return (COMPLETION_SCRIPT % { + 'complete_func': '_%s_completion' % cf_name, + 'script_names': prog_name, + 'autocomplete_var': complete_var, + }).strip() + ';' + + +def resolve_ctx(cli, prog_name, args): + ctx = cli.make_context(prog_name, args, resilient_parsing=True) + while ctx.protected_args + ctx.args and isinstance(ctx.command, MultiCommand): + a = ctx.protected_args + ctx.args + cmd = ctx.command.get_command(ctx, a[0]) + if cmd is None: + return None + ctx = cmd.make_context(a[0], a[1:], parent=ctx, resilient_parsing=True) + return ctx + + +def get_choices(cli, prog_name, args, incomplete): + ctx = resolve_ctx(cli, prog_name, args) + if ctx is None: + return + + choices = [] + if incomplete and not incomplete[:1].isalnum(): + for param in ctx.command.params: + if not isinstance(param, Option): + continue + choices.extend(param.opts) + choices.extend(param.secondary_opts) + elif isinstance(ctx.command, MultiCommand): + choices.extend(ctx.command.list_commands(ctx)) + + for item in choices: + if item.startswith(incomplete): + yield item + + +def do_complete(cli, prog_name): + cwords = split_arg_string(os.environ['COMP_WORDS']) + cword = int(os.environ['COMP_CWORD']) + args = cwords[1:cword] + try: + incomplete = cwords[cword] + except IndexError: + incomplete = '' + + for item in get_choices(cli, prog_name, args, incomplete): + echo(item) + + return True + + +def bashcomplete(cli, prog_name, complete_var, complete_instr): + if complete_instr == 'source': + echo(get_completion_script(prog_name, complete_var)) + return True + elif complete_instr == 'complete': + return do_complete(cli, prog_name) + return False diff --git a/pyextra/click/_compat.py b/pyextra/click/_compat.py new file mode 100644 index 00000000000000..2b43412c4d6026 --- /dev/null +++ b/pyextra/click/_compat.py @@ -0,0 +1,648 @@ +import re +import io +import os +import sys +import codecs +from weakref import WeakKeyDictionary + + +PY2 = sys.version_info[0] == 2 +WIN = sys.platform.startswith('win') +DEFAULT_COLUMNS = 80 + + +_ansi_re = re.compile('\033\[((?:\d|;)*)([a-zA-Z])') + + +def get_filesystem_encoding(): + return sys.getfilesystemencoding() or sys.getdefaultencoding() + + +def _make_text_stream(stream, encoding, errors): + if encoding is None: + encoding = get_best_encoding(stream) + if errors is None: + errors = 'replace' + return _NonClosingTextIOWrapper(stream, encoding, errors, + line_buffering=True) + + +def is_ascii_encoding(encoding): + """Checks if a given encoding is ascii.""" + try: + return codecs.lookup(encoding).name == 'ascii' + except LookupError: + return False + + +def get_best_encoding(stream): + """Returns the default stream encoding if not found.""" + rv = getattr(stream, 'encoding', None) or sys.getdefaultencoding() + if is_ascii_encoding(rv): + return 'utf-8' + return rv + + +class _NonClosingTextIOWrapper(io.TextIOWrapper): + + def __init__(self, stream, encoding, errors, **extra): + self._stream = stream = _FixupStream(stream) + io.TextIOWrapper.__init__(self, stream, encoding, errors, **extra) + + # The io module is a place where the Python 3 text behavior + # was forced upon Python 2, so we need to unbreak + # it to look like Python 2. + if PY2: + def write(self, x): + if isinstance(x, str) or is_bytes(x): + try: + self.flush() + except Exception: + pass + return self.buffer.write(str(x)) + return io.TextIOWrapper.write(self, x) + + def writelines(self, lines): + for line in lines: + self.write(line) + + def __del__(self): + try: + self.detach() + except Exception: + pass + + def isatty(self): + # https://bitbucket.org/pypy/pypy/issue/1803 + return self._stream.isatty() + + +class _FixupStream(object): + """The new io interface needs more from streams than streams + traditionally implement. As such, this fix-up code is necessary in + some circumstances. + """ + + def __init__(self, stream): + self._stream = stream + + def __getattr__(self, name): + return getattr(self._stream, name) + + def read1(self, size): + f = getattr(self._stream, 'read1', None) + if f is not None: + return f(size) + # We only dispatch to readline instead of read in Python 2 as we + # do not want cause problems with the different implementation + # of line buffering. + if PY2: + return self._stream.readline(size) + return self._stream.read(size) + + def readable(self): + x = getattr(self._stream, 'readable', None) + if x is not None: + return x() + try: + self._stream.read(0) + except Exception: + return False + return True + + def writable(self): + x = getattr(self._stream, 'writable', None) + if x is not None: + return x() + try: + self._stream.write('') + except Exception: + try: + self._stream.write(b'') + except Exception: + return False + return True + + def seekable(self): + x = getattr(self._stream, 'seekable', None) + if x is not None: + return x() + try: + self._stream.seek(self._stream.tell()) + except Exception: + return False + return True + + +if PY2: + text_type = unicode + bytes = str + raw_input = raw_input + string_types = (str, unicode) + iteritems = lambda x: x.iteritems() + range_type = xrange + + def is_bytes(x): + return isinstance(x, (buffer, bytearray)) + + _identifier_re = re.compile(r'^[a-zA-Z_][a-zA-Z0-9_]*$') + + # For Windows, we need to force stdout/stdin/stderr to binary if it's + # fetched for that. This obviously is not the most correct way to do + # it as it changes global state. Unfortunately, there does not seem to + # be a clear better way to do it as just reopening the file in binary + # mode does not change anything. + # + # An option would be to do what Python 3 does and to open the file as + # binary only, patch it back to the system, and then use a wrapper + # stream that converts newlines. It's not quite clear what's the + # correct option here. + # + # This code also lives in _winconsole for the fallback to the console + # emulation stream. + # + # There are also Windows environments where the `msvcrt` module is not + # available (which is why we use try-catch instead of the WIN variable + # here), such as the Google App Engine development server on Windows. In + # those cases there is just nothing we can do. + try: + import msvcrt + except ImportError: + set_binary_mode = lambda x: x + else: + def set_binary_mode(f): + try: + fileno = f.fileno() + except Exception: + pass + else: + msvcrt.setmode(fileno, os.O_BINARY) + return f + + def isidentifier(x): + return _identifier_re.search(x) is not None + + def get_binary_stdin(): + return set_binary_mode(sys.stdin) + + def get_binary_stdout(): + return set_binary_mode(sys.stdout) + + def get_binary_stderr(): + return set_binary_mode(sys.stderr) + + def get_text_stdin(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdin, encoding, errors) + if rv is not None: + return rv + return _make_text_stream(sys.stdin, encoding, errors) + + def get_text_stdout(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdout, encoding, errors) + if rv is not None: + return rv + return _make_text_stream(sys.stdout, encoding, errors) + + def get_text_stderr(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stderr, encoding, errors) + if rv is not None: + return rv + return _make_text_stream(sys.stderr, encoding, errors) + + def filename_to_ui(value): + if isinstance(value, bytes): + value = value.decode(get_filesystem_encoding(), 'replace') + return value +else: + import io + text_type = str + raw_input = input + string_types = (str,) + range_type = range + isidentifier = lambda x: x.isidentifier() + iteritems = lambda x: iter(x.items()) + + def is_bytes(x): + return isinstance(x, (bytes, memoryview, bytearray)) + + def _is_binary_reader(stream, default=False): + try: + return isinstance(stream.read(0), bytes) + except Exception: + return default + # This happens in some cases where the stream was already + # closed. In this case, we assume the default. + + def _is_binary_writer(stream, default=False): + try: + stream.write(b'') + except Exception: + try: + stream.write('') + return False + except Exception: + pass + return default + return True + + def _find_binary_reader(stream): + # We need to figure out if the given stream is already binary. + # This can happen because the official docs recommend detaching + # the streams to get binary streams. Some code might do this, so + # we need to deal with this case explicitly. + if _is_binary_reader(stream, False): + return stream + + buf = getattr(stream, 'buffer', None) + + # Same situation here; this time we assume that the buffer is + # actually binary in case it's closed. + if buf is not None and _is_binary_reader(buf, True): + return buf + + def _find_binary_writer(stream): + # We need to figure out if the given stream is already binary. + # This can happen because the official docs recommend detatching + # the streams to get binary streams. Some code might do this, so + # we need to deal with this case explicitly. + if _is_binary_writer(stream, False): + return stream + + buf = getattr(stream, 'buffer', None) + + # Same situation here; this time we assume that the buffer is + # actually binary in case it's closed. + if buf is not None and _is_binary_writer(buf, True): + return buf + + def _stream_is_misconfigured(stream): + """A stream is misconfigured if its encoding is ASCII.""" + # If the stream does not have an encoding set, we assume it's set + # to ASCII. This appears to happen in certain unittest + # environments. It's not quite clear what the correct behavior is + # but this at least will force Click to recover somehow. + return is_ascii_encoding(getattr(stream, 'encoding', None) or 'ascii') + + def _is_compatible_text_stream(stream, encoding, errors): + stream_encoding = getattr(stream, 'encoding', None) + stream_errors = getattr(stream, 'errors', None) + + # Perfect match. + if stream_encoding == encoding and stream_errors == errors: + return True + + # Otherwise, it's only a compatible stream if we did not ask for + # an encoding. + if encoding is None: + return stream_encoding is not None + + return False + + def _force_correct_text_reader(text_reader, encoding, errors): + if _is_binary_reader(text_reader, False): + binary_reader = text_reader + else: + # If there is no target encoding set, we need to verify that the + # reader is not actually misconfigured. + if encoding is None and not _stream_is_misconfigured(text_reader): + return text_reader + + if _is_compatible_text_stream(text_reader, encoding, errors): + return text_reader + + # If the reader has no encoding, we try to find the underlying + # binary reader for it. If that fails because the environment is + # misconfigured, we silently go with the same reader because this + # is too common to happen. In that case, mojibake is better than + # exceptions. + binary_reader = _find_binary_reader(text_reader) + if binary_reader is None: + return text_reader + + # At this point, we default the errors to replace instead of strict + # because nobody handles those errors anyways and at this point + # we're so fundamentally fucked that nothing can repair it. + if errors is None: + errors = 'replace' + return _make_text_stream(binary_reader, encoding, errors) + + def _force_correct_text_writer(text_writer, encoding, errors): + if _is_binary_writer(text_writer, False): + binary_writer = text_writer + else: + # If there is no target encoding set, we need to verify that the + # writer is not actually misconfigured. + if encoding is None and not _stream_is_misconfigured(text_writer): + return text_writer + + if _is_compatible_text_stream(text_writer, encoding, errors): + return text_writer + + # If the writer has no encoding, we try to find the underlying + # binary writer for it. If that fails because the environment is + # misconfigured, we silently go with the same writer because this + # is too common to happen. In that case, mojibake is better than + # exceptions. + binary_writer = _find_binary_writer(text_writer) + if binary_writer is None: + return text_writer + + # At this point, we default the errors to replace instead of strict + # because nobody handles those errors anyways and at this point + # we're so fundamentally fucked that nothing can repair it. + if errors is None: + errors = 'replace' + return _make_text_stream(binary_writer, encoding, errors) + + def get_binary_stdin(): + reader = _find_binary_reader(sys.stdin) + if reader is None: + raise RuntimeError('Was not able to determine binary ' + 'stream for sys.stdin.') + return reader + + def get_binary_stdout(): + writer = _find_binary_writer(sys.stdout) + if writer is None: + raise RuntimeError('Was not able to determine binary ' + 'stream for sys.stdout.') + return writer + + def get_binary_stderr(): + writer = _find_binary_writer(sys.stderr) + if writer is None: + raise RuntimeError('Was not able to determine binary ' + 'stream for sys.stderr.') + return writer + + def get_text_stdin(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdin, encoding, errors) + if rv is not None: + return rv + return _force_correct_text_reader(sys.stdin, encoding, errors) + + def get_text_stdout(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdout, encoding, errors) + if rv is not None: + return rv + return _force_correct_text_writer(sys.stdout, encoding, errors) + + def get_text_stderr(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stderr, encoding, errors) + if rv is not None: + return rv + return _force_correct_text_writer(sys.stderr, encoding, errors) + + def filename_to_ui(value): + if isinstance(value, bytes): + value = value.decode(get_filesystem_encoding(), 'replace') + else: + value = value.encode('utf-8', 'surrogateescape') \ + .decode('utf-8', 'replace') + return value + + +def get_streerror(e, default=None): + if hasattr(e, 'strerror'): + msg = e.strerror + else: + if default is not None: + msg = default + else: + msg = str(e) + if isinstance(msg, bytes): + msg = msg.decode('utf-8', 'replace') + return msg + + +def open_stream(filename, mode='r', encoding=None, errors='strict', + atomic=False): + # Standard streams first. These are simple because they don't need + # special handling for the atomic flag. It's entirely ignored. + if filename == '-': + if 'w' in mode: + if 'b' in mode: + return get_binary_stdout(), False + return get_text_stdout(encoding=encoding, errors=errors), False + if 'b' in mode: + return get_binary_stdin(), False + return get_text_stdin(encoding=encoding, errors=errors), False + + # Non-atomic writes directly go out through the regular open functions. + if not atomic: + if encoding is None: + return open(filename, mode), True + return io.open(filename, mode, encoding=encoding, errors=errors), True + + # Some usability stuff for atomic writes + if 'a' in mode: + raise ValueError( + 'Appending to an existing file is not supported, because that ' + 'would involve an expensive `copy`-operation to a temporary ' + 'file. Open the file in normal `w`-mode and copy explicitly ' + 'if that\'s what you\'re after.' + ) + if 'x' in mode: + raise ValueError('Use the `overwrite`-parameter instead.') + if 'w' not in mode: + raise ValueError('Atomic writes only make sense with `w`-mode.') + + # Atomic writes are more complicated. They work by opening a file + # as a proxy in the same folder and then using the fdopen + # functionality to wrap it in a Python file. Then we wrap it in an + # atomic file that moves the file over on close. + import tempfile + fd, tmp_filename = tempfile.mkstemp(dir=os.path.dirname(filename), + prefix='.__atomic-write') + + if encoding is not None: + f = io.open(fd, mode, encoding=encoding, errors=errors) + else: + f = os.fdopen(fd, mode) + + return _AtomicFile(f, tmp_filename, filename), True + + +# Used in a destructor call, needs extra protection from interpreter cleanup. +if hasattr(os, 'replace'): + _replace = os.replace + _can_replace = True +else: + _replace = os.rename + _can_replace = not WIN + + +class _AtomicFile(object): + + def __init__(self, f, tmp_filename, real_filename): + self._f = f + self._tmp_filename = tmp_filename + self._real_filename = real_filename + self.closed = False + + @property + def name(self): + return self._real_filename + + def close(self, delete=False): + if self.closed: + return + self._f.close() + if not _can_replace: + try: + os.remove(self._real_filename) + except OSError: + pass + _replace(self._tmp_filename, self._real_filename) + self.closed = True + + def __getattr__(self, name): + return getattr(self._f, name) + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close(delete=exc_type is not None) + + def __repr__(self): + return repr(self._f) + + +auto_wrap_for_ansi = None +colorama = None +get_winterm_size = None + + +def strip_ansi(value): + return _ansi_re.sub('', value) + + +def should_strip_ansi(stream=None, color=None): + if color is None: + if stream is None: + stream = sys.stdin + return not isatty(stream) + return not color + + +# If we're on Windows, we provide transparent integration through +# colorama. This will make ANSI colors through the echo function +# work automatically. +if WIN: + # Windows has a smaller terminal + DEFAULT_COLUMNS = 79 + + from ._winconsole import _get_windows_console_stream + + def _get_argv_encoding(): + import locale + return locale.getpreferredencoding() + + if PY2: + def raw_input(prompt=''): + sys.stderr.flush() + if prompt: + stdout = _default_text_stdout() + stdout.write(prompt) + stdin = _default_text_stdin() + return stdin.readline().rstrip('\r\n') + + try: + import colorama + except ImportError: + pass + else: + _ansi_stream_wrappers = WeakKeyDictionary() + + def auto_wrap_for_ansi(stream, color=None): + """This function wraps a stream so that calls through colorama + are issued to the win32 console API to recolor on demand. It + also ensures to reset the colors if a write call is interrupted + to not destroy the console afterwards. + """ + try: + cached = _ansi_stream_wrappers.get(stream) + except Exception: + cached = None + if cached is not None: + return cached + strip = should_strip_ansi(stream, color) + ansi_wrapper = colorama.AnsiToWin32(stream, strip=strip) + rv = ansi_wrapper.stream + _write = rv.write + + def _safe_write(s): + try: + return _write(s) + except: + ansi_wrapper.reset_all() + raise + + rv.write = _safe_write + try: + _ansi_stream_wrappers[stream] = rv + except Exception: + pass + return rv + + def get_winterm_size(): + win = colorama.win32.GetConsoleScreenBufferInfo( + colorama.win32.STDOUT).srWindow + return win.Right - win.Left, win.Bottom - win.Top +else: + def _get_argv_encoding(): + return getattr(sys.stdin, 'encoding', None) or get_filesystem_encoding() + + _get_windows_console_stream = lambda *x: None + + +def term_len(x): + return len(strip_ansi(x)) + + +def isatty(stream): + try: + return stream.isatty() + except Exception: + return False + + +def _make_cached_stream_func(src_func, wrapper_func): + cache = WeakKeyDictionary() + def func(): + stream = src_func() + try: + rv = cache.get(stream) + except Exception: + rv = None + if rv is not None: + return rv + rv = wrapper_func() + try: + cache[stream] = rv + except Exception: + pass + return rv + return func + + +_default_text_stdin = _make_cached_stream_func( + lambda: sys.stdin, get_text_stdin) +_default_text_stdout = _make_cached_stream_func( + lambda: sys.stdout, get_text_stdout) +_default_text_stderr = _make_cached_stream_func( + lambda: sys.stderr, get_text_stderr) + + +binary_streams = { + 'stdin': get_binary_stdin, + 'stdout': get_binary_stdout, + 'stderr': get_binary_stderr, +} + +text_streams = { + 'stdin': get_text_stdin, + 'stdout': get_text_stdout, + 'stderr': get_text_stderr, +} diff --git a/pyextra/click/_termui_impl.py b/pyextra/click/_termui_impl.py new file mode 100644 index 00000000000000..7cfd3d5c4a058b --- /dev/null +++ b/pyextra/click/_termui_impl.py @@ -0,0 +1,547 @@ +""" + click._termui_impl + ~~~~~~~~~~~~~~~~~~ + + This module contains implementations for the termui module. To keep the + import time of Click down, some infrequently used functionality is placed + in this module and only imported as needed. + + :copyright: (c) 2014 by Armin Ronacher. + :license: BSD, see LICENSE for more details. +""" +import os +import sys +import time +import math +from ._compat import _default_text_stdout, range_type, PY2, isatty, \ + open_stream, strip_ansi, term_len, get_best_encoding, WIN +from .utils import echo +from .exceptions import ClickException + + +if os.name == 'nt': + BEFORE_BAR = '\r' + AFTER_BAR = '\n' +else: + BEFORE_BAR = '\r\033[?25l' + AFTER_BAR = '\033[?25h\n' + + +def _length_hint(obj): + """Returns the length hint of an object.""" + try: + return len(obj) + except (AttributeError, TypeError): + try: + get_hint = type(obj).__length_hint__ + except AttributeError: + return None + try: + hint = get_hint(obj) + except TypeError: + return None + if hint is NotImplemented or \ + not isinstance(hint, (int, long)) or \ + hint < 0: + return None + return hint + + +class ProgressBar(object): + + def __init__(self, iterable, length=None, fill_char='#', empty_char=' ', + bar_template='%(bar)s', info_sep=' ', show_eta=True, + show_percent=None, show_pos=False, item_show_func=None, + label=None, file=None, color=None, width=30): + self.fill_char = fill_char + self.empty_char = empty_char + self.bar_template = bar_template + self.info_sep = info_sep + self.show_eta = show_eta + self.show_percent = show_percent + self.show_pos = show_pos + self.item_show_func = item_show_func + self.label = label or '' + if file is None: + file = _default_text_stdout() + self.file = file + self.color = color + self.width = width + self.autowidth = width == 0 + + if length is None: + length = _length_hint(iterable) + if iterable is None: + if length is None: + raise TypeError('iterable or length is required') + iterable = range_type(length) + self.iter = iter(iterable) + self.length = length + self.length_known = length is not None + self.pos = 0 + self.avg = [] + self.start = self.last_eta = time.time() + self.eta_known = False + self.finished = False + self.max_width = None + self.entered = False + self.current_item = None + self.is_hidden = not isatty(self.file) + self._last_line = None + + def __enter__(self): + self.entered = True + self.render_progress() + return self + + def __exit__(self, exc_type, exc_value, tb): + self.render_finish() + + def __iter__(self): + if not self.entered: + raise RuntimeError('You need to use progress bars in a with block.') + self.render_progress() + return self + + def render_finish(self): + if self.is_hidden: + return + self.file.write(AFTER_BAR) + self.file.flush() + + @property + def pct(self): + if self.finished: + return 1.0 + return min(self.pos / (float(self.length) or 1), 1.0) + + @property + def time_per_iteration(self): + if not self.avg: + return 0.0 + return sum(self.avg) / float(len(self.avg)) + + @property + def eta(self): + if self.length_known and not self.finished: + return self.time_per_iteration * (self.length - self.pos) + return 0.0 + + def format_eta(self): + if self.eta_known: + t = self.eta + 1 + seconds = t % 60 + t /= 60 + minutes = t % 60 + t /= 60 + hours = t % 24 + t /= 24 + if t > 0: + days = t + return '%dd %02d:%02d:%02d' % (days, hours, minutes, seconds) + else: + return '%02d:%02d:%02d' % (hours, minutes, seconds) + return '' + + def format_pos(self): + pos = str(self.pos) + if self.length_known: + pos += '/%s' % self.length + return pos + + def format_pct(self): + return ('% 4d%%' % int(self.pct * 100))[1:] + + def format_progress_line(self): + show_percent = self.show_percent + + info_bits = [] + if self.length_known: + bar_length = int(self.pct * self.width) + bar = self.fill_char * bar_length + bar += self.empty_char * (self.width - bar_length) + if show_percent is None: + show_percent = not self.show_pos + else: + if self.finished: + bar = self.fill_char * self.width + else: + bar = list(self.empty_char * (self.width or 1)) + if self.time_per_iteration != 0: + bar[int((math.cos(self.pos * self.time_per_iteration) + / 2.0 + 0.5) * self.width)] = self.fill_char + bar = ''.join(bar) + + if self.show_pos: + info_bits.append(self.format_pos()) + if show_percent: + info_bits.append(self.format_pct()) + if self.show_eta and self.eta_known and not self.finished: + info_bits.append(self.format_eta()) + if self.item_show_func is not None: + item_info = self.item_show_func(self.current_item) + if item_info is not None: + info_bits.append(item_info) + + return (self.bar_template % { + 'label': self.label, + 'bar': bar, + 'info': self.info_sep.join(info_bits) + }).rstrip() + + def render_progress(self): + from .termui import get_terminal_size + nl = False + + if self.is_hidden: + buf = [self.label] + nl = True + else: + buf = [] + # Update width in case the terminal has been resized + if self.autowidth: + old_width = self.width + self.width = 0 + clutter_length = term_len(self.format_progress_line()) + new_width = max(0, get_terminal_size()[0] - clutter_length) + if new_width < old_width: + buf.append(BEFORE_BAR) + buf.append(' ' * self.max_width) + self.max_width = new_width + self.width = new_width + + clear_width = self.width + if self.max_width is not None: + clear_width = self.max_width + + buf.append(BEFORE_BAR) + line = self.format_progress_line() + line_len = term_len(line) + if self.max_width is None or self.max_width < line_len: + self.max_width = line_len + buf.append(line) + + buf.append(' ' * (clear_width - line_len)) + line = ''.join(buf) + + # Render the line only if it changed. + if line != self._last_line: + self._last_line = line + echo(line, file=self.file, color=self.color, nl=nl) + self.file.flush() + + def make_step(self, n_steps): + self.pos += n_steps + if self.length_known and self.pos >= self.length: + self.finished = True + + if (time.time() - self.last_eta) < 1.0: + return + + self.last_eta = time.time() + self.avg = self.avg[-6:] + [-(self.start - time.time()) / (self.pos)] + + self.eta_known = self.length_known + + def update(self, n_steps): + self.make_step(n_steps) + self.render_progress() + + def finish(self): + self.eta_known = 0 + self.current_item = None + self.finished = True + + def next(self): + if self.is_hidden: + return next(self.iter) + try: + rv = next(self.iter) + self.current_item = rv + except StopIteration: + self.finish() + self.render_progress() + raise StopIteration() + else: + self.update(1) + return rv + + if not PY2: + __next__ = next + del next + + +def pager(text, color=None): + """Decide what method to use for paging through text.""" + stdout = _default_text_stdout() + if not isatty(sys.stdin) or not isatty(stdout): + return _nullpager(stdout, text, color) + pager_cmd = (os.environ.get('PAGER', None) or '').strip() + if pager_cmd: + if WIN: + return _tempfilepager(text, pager_cmd, color) + return _pipepager(text, pager_cmd, color) + if os.environ.get('TERM') in ('dumb', 'emacs'): + return _nullpager(stdout, text, color) + if WIN or sys.platform.startswith('os2'): + return _tempfilepager(text, 'more <', color) + if hasattr(os, 'system') and os.system('(less) 2>/dev/null') == 0: + return _pipepager(text, 'less', color) + + import tempfile + fd, filename = tempfile.mkstemp() + os.close(fd) + try: + if hasattr(os, 'system') and os.system('more "%s"' % filename) == 0: + return _pipepager(text, 'more', color) + return _nullpager(stdout, text, color) + finally: + os.unlink(filename) + + +def _pipepager(text, cmd, color): + """Page through text by feeding it to another program. Invoking a + pager through this might support colors. + """ + import subprocess + env = dict(os.environ) + + # If we're piping to less we might support colors under the + # condition that + cmd_detail = cmd.rsplit('/', 1)[-1].split() + if color is None and cmd_detail[0] == 'less': + less_flags = os.environ.get('LESS', '') + ' '.join(cmd_detail[1:]) + if not less_flags: + env['LESS'] = '-R' + color = True + elif 'r' in less_flags or 'R' in less_flags: + color = True + + if not color: + text = strip_ansi(text) + + c = subprocess.Popen(cmd, shell=True, stdin=subprocess.PIPE, + env=env) + encoding = get_best_encoding(c.stdin) + try: + c.stdin.write(text.encode(encoding, 'replace')) + c.stdin.close() + except (IOError, KeyboardInterrupt): + pass + + # Less doesn't respect ^C, but catches it for its own UI purposes (aborting + # search or other commands inside less). + # + # That means when the user hits ^C, the parent process (click) terminates, + # but less is still alive, paging the output and messing up the terminal. + # + # If the user wants to make the pager exit on ^C, they should set + # `LESS='-K'`. It's not our decision to make. + while True: + try: + c.wait() + except KeyboardInterrupt: + pass + else: + break + + +def _tempfilepager(text, cmd, color): + """Page through text by invoking a program on a temporary file.""" + import tempfile + filename = tempfile.mktemp() + if not color: + text = strip_ansi(text) + encoding = get_best_encoding(sys.stdout) + with open_stream(filename, 'wb')[0] as f: + f.write(text.encode(encoding)) + try: + os.system(cmd + ' "' + filename + '"') + finally: + os.unlink(filename) + + +def _nullpager(stream, text, color): + """Simply print unformatted text. This is the ultimate fallback.""" + if not color: + text = strip_ansi(text) + stream.write(text) + + +class Editor(object): + + def __init__(self, editor=None, env=None, require_save=True, + extension='.txt'): + self.editor = editor + self.env = env + self.require_save = require_save + self.extension = extension + + def get_editor(self): + if self.editor is not None: + return self.editor + for key in 'VISUAL', 'EDITOR': + rv = os.environ.get(key) + if rv: + return rv + if WIN: + return 'notepad' + for editor in 'vim', 'nano': + if os.system('which %s >/dev/null 2>&1' % editor) == 0: + return editor + return 'vi' + + def edit_file(self, filename): + import subprocess + editor = self.get_editor() + if self.env: + environ = os.environ.copy() + environ.update(self.env) + else: + environ = None + try: + c = subprocess.Popen('%s "%s"' % (editor, filename), + env=environ, shell=True) + exit_code = c.wait() + if exit_code != 0: + raise ClickException('%s: Editing failed!' % editor) + except OSError as e: + raise ClickException('%s: Editing failed: %s' % (editor, e)) + + def edit(self, text): + import tempfile + + text = text or '' + if text and not text.endswith('\n'): + text += '\n' + + fd, name = tempfile.mkstemp(prefix='editor-', suffix=self.extension) + try: + if WIN: + encoding = 'utf-8-sig' + text = text.replace('\n', '\r\n') + else: + encoding = 'utf-8' + text = text.encode(encoding) + + f = os.fdopen(fd, 'wb') + f.write(text) + f.close() + timestamp = os.path.getmtime(name) + + self.edit_file(name) + + if self.require_save \ + and os.path.getmtime(name) == timestamp: + return None + + f = open(name, 'rb') + try: + rv = f.read() + finally: + f.close() + return rv.decode('utf-8-sig').replace('\r\n', '\n') + finally: + os.unlink(name) + + +def open_url(url, wait=False, locate=False): + import subprocess + + def _unquote_file(url): + try: + import urllib + except ImportError: + import urllib + if url.startswith('file://'): + url = urllib.unquote(url[7:]) + return url + + if sys.platform == 'darwin': + args = ['open'] + if wait: + args.append('-W') + if locate: + args.append('-R') + args.append(_unquote_file(url)) + null = open('/dev/null', 'w') + try: + return subprocess.Popen(args, stderr=null).wait() + finally: + null.close() + elif WIN: + if locate: + url = _unquote_file(url) + args = 'explorer /select,"%s"' % _unquote_file( + url.replace('"', '')) + else: + args = 'start %s "" "%s"' % ( + wait and '/WAIT' or '', url.replace('"', '')) + return os.system(args) + + try: + if locate: + url = os.path.dirname(_unquote_file(url)) or '.' + else: + url = _unquote_file(url) + c = subprocess.Popen(['xdg-open', url]) + if wait: + return c.wait() + return 0 + except OSError: + if url.startswith(('http://', 'https://')) and not locate and not wait: + import webbrowser + webbrowser.open(url) + return 0 + return 1 + + +def _translate_ch_to_exc(ch): + if ch == '\x03': + raise KeyboardInterrupt() + if ch == '\x04': + raise EOFError() + + +if WIN: + import msvcrt + + def getchar(echo): + rv = msvcrt.getch() + if echo: + msvcrt.putchar(rv) + _translate_ch_to_exc(rv) + if PY2: + enc = getattr(sys.stdin, 'encoding', None) + if enc is not None: + rv = rv.decode(enc, 'replace') + else: + rv = rv.decode('cp1252', 'replace') + return rv +else: + import tty + import termios + + def getchar(echo): + if not isatty(sys.stdin): + f = open('/dev/tty') + fd = f.fileno() + else: + fd = sys.stdin.fileno() + f = None + try: + old_settings = termios.tcgetattr(fd) + try: + tty.setraw(fd) + ch = os.read(fd, 32) + if echo and isatty(sys.stdout): + sys.stdout.write(ch) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + sys.stdout.flush() + if f is not None: + f.close() + except termios.error: + pass + _translate_ch_to_exc(ch) + return ch.decode(get_best_encoding(sys.stdin), 'replace') diff --git a/pyextra/click/_textwrap.py b/pyextra/click/_textwrap.py new file mode 100644 index 00000000000000..7e776031eaa929 --- /dev/null +++ b/pyextra/click/_textwrap.py @@ -0,0 +1,38 @@ +import textwrap +from contextlib import contextmanager + + +class TextWrapper(textwrap.TextWrapper): + + def _handle_long_word(self, reversed_chunks, cur_line, cur_len, width): + space_left = max(width - cur_len, 1) + + if self.break_long_words: + last = reversed_chunks[-1] + cut = last[:space_left] + res = last[space_left:] + cur_line.append(cut) + reversed_chunks[-1] = res + elif not cur_line: + cur_line.append(reversed_chunks.pop()) + + @contextmanager + def extra_indent(self, indent): + old_initial_indent = self.initial_indent + old_subsequent_indent = self.subsequent_indent + self.initial_indent += indent + self.subsequent_indent += indent + try: + yield + finally: + self.initial_indent = old_initial_indent + self.subsequent_indent = old_subsequent_indent + + def indent_only(self, text): + rv = [] + for idx, line in enumerate(text.splitlines()): + indent = self.initial_indent + if idx > 0: + indent = self.subsequent_indent + rv.append(indent + line) + return '\n'.join(rv) diff --git a/pyextra/click/_unicodefun.py b/pyextra/click/_unicodefun.py new file mode 100644 index 00000000000000..9e17a384eff036 --- /dev/null +++ b/pyextra/click/_unicodefun.py @@ -0,0 +1,118 @@ +import os +import sys +import codecs + +from ._compat import PY2 + + +# If someone wants to vendor click, we want to ensure the +# correct package is discovered. Ideally we could use a +# relative import here but unfortunately Python does not +# support that. +click = sys.modules[__name__.rsplit('.', 1)[0]] + + +def _find_unicode_literals_frame(): + import __future__ + frm = sys._getframe(1) + idx = 1 + while frm is not None: + if frm.f_globals.get('__name__', '').startswith('click.'): + frm = frm.f_back + idx += 1 + elif frm.f_code.co_flags & __future__.unicode_literals.compiler_flag: + return idx + else: + break + return 0 + + +def _check_for_unicode_literals(): + if not __debug__: + return + if not PY2 or click.disable_unicode_literals_warning: + return + bad_frame = _find_unicode_literals_frame() + if bad_frame <= 0: + return + from warnings import warn + warn(Warning('Click detected the use of the unicode_literals ' + '__future__ import. This is heavily discouraged ' + 'because it can introduce subtle bugs in your ' + 'code. You should instead use explicit u"" literals ' + 'for your unicode strings. For more information see ' + 'http://click.pocoo.org/python3/'), + stacklevel=bad_frame) + + +def _verify_python3_env(): + """Ensures that the environment is good for unicode on Python 3.""" + if PY2: + return + try: + import locale + fs_enc = codecs.lookup(locale.getpreferredencoding()).name + except Exception: + fs_enc = 'ascii' + if fs_enc != 'ascii': + return + + extra = '' + if os.name == 'posix': + import subprocess + rv = subprocess.Popen(['locale', '-a'], stdout=subprocess.PIPE, + stderr=subprocess.PIPE).communicate()[0] + good_locales = set() + has_c_utf8 = False + + # Make sure we're operating on text here. + if isinstance(rv, bytes): + rv = rv.decode('ascii', 'replace') + + for line in rv.splitlines(): + locale = line.strip() + if locale.lower().endswith(('.utf-8', '.utf8')): + good_locales.add(locale) + if locale.lower() in ('c.utf8', 'c.utf-8'): + has_c_utf8 = True + + extra += '\n\n' + if not good_locales: + extra += ( + 'Additional information: on this system no suitable UTF-8\n' + 'locales were discovered. This most likely requires resolving\n' + 'by reconfiguring the locale system.' + ) + elif has_c_utf8: + extra += ( + 'This system supports the C.UTF-8 locale which is recommended.\n' + 'You might be able to resolve your issue by exporting the\n' + 'following environment variables:\n\n' + ' export LC_ALL=C.UTF-8\n' + ' export LANG=C.UTF-8' + ) + else: + extra += ( + 'This system lists a couple of UTF-8 supporting locales that\n' + 'you can pick from. The following suitable locales where\n' + 'discovered: %s' + ) % ', '.join(sorted(good_locales)) + + bad_locale = None + for locale in os.environ.get('LC_ALL'), os.environ.get('LANG'): + if locale and locale.lower().endswith(('.utf-8', '.utf8')): + bad_locale = locale + if locale is not None: + break + if bad_locale is not None: + extra += ( + '\n\nClick discovered that you exported a UTF-8 locale\n' + 'but the locale system could not pick up from it because\n' + 'it does not exist. The exported locale is "%s" but it\n' + 'is not supported' + ) % bad_locale + + raise RuntimeError('Click will abort further execution because Python 3 ' + 'was configured to use ASCII as encoding for the ' + 'environment. Consult http://click.pocoo.org/python3/' + 'for mitigation steps.' + extra) diff --git a/pyextra/click/_winconsole.py b/pyextra/click/_winconsole.py new file mode 100644 index 00000000000000..9aed942162bbdd --- /dev/null +++ b/pyextra/click/_winconsole.py @@ -0,0 +1,273 @@ +# -*- coding: utf-8 -*- +# This module is based on the excellent work by Adam Bartoš who +# provided a lot of what went into the implementation here in +# the discussion to issue1602 in the Python bug tracker. +# +# There are some general differences in regards to how this works +# compared to the original patches as we do not need to patch +# the entire interpreter but just work in our little world of +# echo and prmopt. + +import io +import os +import sys +import zlib +import time +import ctypes +import msvcrt +from click._compat import _NonClosingTextIOWrapper, text_type, PY2 +from ctypes import byref, POINTER, c_int, c_char, c_char_p, \ + c_void_p, py_object, c_ssize_t, c_ulong, windll, WINFUNCTYPE +try: + from ctypes import pythonapi + PyObject_GetBuffer = pythonapi.PyObject_GetBuffer + PyBuffer_Release = pythonapi.PyBuffer_Release +except ImportError: + pythonapi = None +from ctypes.wintypes import LPWSTR, LPCWSTR + + +c_ssize_p = POINTER(c_ssize_t) + +kernel32 = windll.kernel32 +GetStdHandle = kernel32.GetStdHandle +ReadConsoleW = kernel32.ReadConsoleW +WriteConsoleW = kernel32.WriteConsoleW +GetLastError = kernel32.GetLastError +GetCommandLineW = WINFUNCTYPE(LPWSTR)( + ('GetCommandLineW', windll.kernel32)) +CommandLineToArgvW = WINFUNCTYPE( + POINTER(LPWSTR), LPCWSTR, POINTER(c_int))( + ('CommandLineToArgvW', windll.shell32)) + + +STDIN_HANDLE = GetStdHandle(-10) +STDOUT_HANDLE = GetStdHandle(-11) +STDERR_HANDLE = GetStdHandle(-12) + + +PyBUF_SIMPLE = 0 +PyBUF_WRITABLE = 1 + +ERROR_SUCCESS = 0 +ERROR_NOT_ENOUGH_MEMORY = 8 +ERROR_OPERATION_ABORTED = 995 + +STDIN_FILENO = 0 +STDOUT_FILENO = 1 +STDERR_FILENO = 2 + +EOF = b'\x1a' +MAX_BYTES_WRITTEN = 32767 + + +class Py_buffer(ctypes.Structure): + _fields_ = [ + ('buf', c_void_p), + ('obj', py_object), + ('len', c_ssize_t), + ('itemsize', c_ssize_t), + ('readonly', c_int), + ('ndim', c_int), + ('format', c_char_p), + ('shape', c_ssize_p), + ('strides', c_ssize_p), + ('suboffsets', c_ssize_p), + ('internal', c_void_p) + ] + + if PY2: + _fields_.insert(-1, ('smalltable', c_ssize_t * 2)) + + +# On PyPy we cannot get buffers so our ability to operate here is +# serverly limited. +if pythonapi is None: + get_buffer = None +else: + def get_buffer(obj, writable=False): + buf = Py_buffer() + flags = PyBUF_WRITABLE if writable else PyBUF_SIMPLE + PyObject_GetBuffer(py_object(obj), byref(buf), flags) + try: + buffer_type = c_char * buf.len + return buffer_type.from_address(buf.buf) + finally: + PyBuffer_Release(byref(buf)) + + +class _WindowsConsoleRawIOBase(io.RawIOBase): + + def __init__(self, handle): + self.handle = handle + + def isatty(self): + io.RawIOBase.isatty(self) + return True + + +class _WindowsConsoleReader(_WindowsConsoleRawIOBase): + + def readable(self): + return True + + def readinto(self, b): + bytes_to_be_read = len(b) + if not bytes_to_be_read: + return 0 + elif bytes_to_be_read % 2: + raise ValueError('cannot read odd number of bytes from ' + 'UTF-16-LE encoded console') + + buffer = get_buffer(b, writable=True) + code_units_to_be_read = bytes_to_be_read // 2 + code_units_read = c_ulong() + + rv = ReadConsoleW(self.handle, buffer, code_units_to_be_read, + byref(code_units_read), None) + if GetLastError() == ERROR_OPERATION_ABORTED: + # wait for KeyboardInterrupt + time.sleep(0.1) + if not rv: + raise OSError('Windows error: %s' % GetLastError()) + + if buffer[0] == EOF: + return 0 + return 2 * code_units_read.value + + +class _WindowsConsoleWriter(_WindowsConsoleRawIOBase): + + def writable(self): + return True + + @staticmethod + def _get_error_message(errno): + if errno == ERROR_SUCCESS: + return 'ERROR_SUCCESS' + elif errno == ERROR_NOT_ENOUGH_MEMORY: + return 'ERROR_NOT_ENOUGH_MEMORY' + return 'Windows error %s' % errno + + def write(self, b): + bytes_to_be_written = len(b) + buf = get_buffer(b) + code_units_to_be_written = min(bytes_to_be_written, + MAX_BYTES_WRITTEN) // 2 + code_units_written = c_ulong() + + WriteConsoleW(self.handle, buf, code_units_to_be_written, + byref(code_units_written), None) + bytes_written = 2 * code_units_written.value + + if bytes_written == 0 and bytes_to_be_written > 0: + raise OSError(self._get_error_message(GetLastError())) + return bytes_written + + +class ConsoleStream(object): + + def __init__(self, text_stream, byte_stream): + self._text_stream = text_stream + self.buffer = byte_stream + + @property + def name(self): + return self.buffer.name + + def write(self, x): + if isinstance(x, text_type): + return self._text_stream.write(x) + try: + self.flush() + except Exception: + pass + return self.buffer.write(x) + + def writelines(self, lines): + for line in lines: + self.write(line) + + def __getattr__(self, name): + return getattr(self._text_stream, name) + + def isatty(self): + return self.buffer.isatty() + + def __repr__(self): + return '' % ( + self.name, + self.encoding, + ) + + +def _get_text_stdin(buffer_stream): + text_stream = _NonClosingTextIOWrapper( + io.BufferedReader(_WindowsConsoleReader(STDIN_HANDLE)), + 'utf-16-le', 'strict', line_buffering=True) + return ConsoleStream(text_stream, buffer_stream) + + +def _get_text_stdout(buffer_stream): + text_stream = _NonClosingTextIOWrapper( + _WindowsConsoleWriter(STDOUT_HANDLE), + 'utf-16-le', 'strict', line_buffering=True) + return ConsoleStream(text_stream, buffer_stream) + + +def _get_text_stderr(buffer_stream): + text_stream = _NonClosingTextIOWrapper( + _WindowsConsoleWriter(STDERR_HANDLE), + 'utf-16-le', 'strict', line_buffering=True) + return ConsoleStream(text_stream, buffer_stream) + + +if PY2: + def _hash_py_argv(): + return zlib.crc32('\x00'.join(sys.argv[1:])) + + _initial_argv_hash = _hash_py_argv() + + def _get_windows_argv(): + argc = c_int(0) + argv_unicode = CommandLineToArgvW(GetCommandLineW(), byref(argc)) + argv = [argv_unicode[i] for i in range(0, argc.value)] + + if not hasattr(sys, 'frozen'): + argv = argv[1:] + while len(argv) > 0: + arg = argv[0] + if not arg.startswith('-') or arg == '-': + break + argv = argv[1:] + if arg.startswith(('-c', '-m')): + break + + return argv[1:] + + +_stream_factories = { + 0: _get_text_stdin, + 1: _get_text_stdout, + 2: _get_text_stderr, +} + + +def _get_windows_console_stream(f, encoding, errors): + if get_buffer is not None and \ + encoding in ('utf-16-le', None) \ + and errors in ('strict', None) and \ + hasattr(f, 'isatty') and f.isatty(): + func = _stream_factories.get(f.fileno()) + if func is not None: + if not PY2: + f = getattr(f, 'buffer') + if f is None: + return None + else: + # If we are on Python 2 we need to set the stream that we + # deal with to binary mode as otherwise the exercise if a + # bit moot. The same problems apply as for + # get_binary_stdin and friends from _compat. + msvcrt.setmode(f.fileno(), os.O_BINARY) + return func(f) diff --git a/pyextra/click/core.py b/pyextra/click/core.py new file mode 100644 index 00000000000000..74564514753131 --- /dev/null +++ b/pyextra/click/core.py @@ -0,0 +1,1744 @@ +import errno +import os +import sys +from contextlib import contextmanager +from itertools import repeat +from functools import update_wrapper + +from .types import convert_type, IntRange, BOOL +from .utils import make_str, make_default_short_help, echo, get_os_args +from .exceptions import ClickException, UsageError, BadParameter, Abort, \ + MissingParameter +from .termui import prompt, confirm +from .formatting import HelpFormatter, join_options +from .parser import OptionParser, split_opt +from .globals import push_context, pop_context + +from ._compat import PY2, isidentifier, iteritems +from ._unicodefun import _check_for_unicode_literals, _verify_python3_env + + +_missing = object() + + +SUBCOMMAND_METAVAR = 'COMMAND [ARGS]...' +SUBCOMMANDS_METAVAR = 'COMMAND1 [ARGS]... [COMMAND2 [ARGS]...]...' + + +def _bashcomplete(cmd, prog_name, complete_var=None): + """Internal handler for the bash completion support.""" + if complete_var is None: + complete_var = '_%s_COMPLETE' % (prog_name.replace('-', '_')).upper() + complete_instr = os.environ.get(complete_var) + if not complete_instr: + return + + from ._bashcomplete import bashcomplete + if bashcomplete(cmd, prog_name, complete_var, complete_instr): + sys.exit(1) + + +def _check_multicommand(base_command, cmd_name, cmd, register=False): + if not base_command.chain or not isinstance(cmd, MultiCommand): + return + if register: + hint = 'It is not possible to add multi commands as children to ' \ + 'another multi command that is in chain mode' + else: + hint = 'Found a multi command as subcommand to a multi command ' \ + 'that is in chain mode. This is not supported' + raise RuntimeError('%s. Command "%s" is set to chain and "%s" was ' + 'added as subcommand but it in itself is a ' + 'multi command. ("%s" is a %s within a chained ' + '%s named "%s"). This restriction was supposed to ' + 'be lifted in 6.0 but the fix was flawed. This ' + 'will be fixed in Click 7.0' % ( + hint, base_command.name, cmd_name, + cmd_name, cmd.__class__.__name__, + base_command.__class__.__name__, + base_command.name)) + + +def batch(iterable, batch_size): + return list(zip(*repeat(iter(iterable), batch_size))) + + +def invoke_param_callback(callback, ctx, param, value): + code = getattr(callback, '__code__', None) + args = getattr(code, 'co_argcount', 3) + + if args < 3: + # This will become a warning in Click 3.0: + from warnings import warn + warn(Warning('Invoked legacy parameter callback "%s". The new ' + 'signature for such callbacks starting with ' + 'click 2.0 is (ctx, param, value).' + % callback), stacklevel=3) + return callback(ctx, value) + return callback(ctx, param, value) + + +@contextmanager +def augment_usage_errors(ctx, param=None): + """Context manager that attaches extra information to exceptions that + fly. + """ + try: + yield + except BadParameter as e: + if e.ctx is None: + e.ctx = ctx + if param is not None and e.param is None: + e.param = param + raise + except UsageError as e: + if e.ctx is None: + e.ctx = ctx + raise + + +def iter_params_for_processing(invocation_order, declaration_order): + """Given a sequence of parameters in the order as should be considered + for processing and an iterable of parameters that exist, this returns + a list in the correct order as they should be processed. + """ + def sort_key(item): + try: + idx = invocation_order.index(item) + except ValueError: + idx = float('inf') + return (not item.is_eager, idx) + + return sorted(declaration_order, key=sort_key) + + +class Context(object): + """The context is a special internal object that holds state relevant + for the script execution at every single level. It's normally invisible + to commands unless they opt-in to getting access to it. + + The context is useful as it can pass internal objects around and can + control special execution features such as reading data from + environment variables. + + A context can be used as context manager in which case it will call + :meth:`close` on teardown. + + .. versionadded:: 2.0 + Added the `resilient_parsing`, `help_option_names`, + `token_normalize_func` parameters. + + .. versionadded:: 3.0 + Added the `allow_extra_args` and `allow_interspersed_args` + parameters. + + .. versionadded:: 4.0 + Added the `color`, `ignore_unknown_options`, and + `max_content_width` parameters. + + :param command: the command class for this context. + :param parent: the parent context. + :param info_name: the info name for this invocation. Generally this + is the most descriptive name for the script or + command. For the toplevel script it is usually + the name of the script, for commands below it it's + the name of the script. + :param obj: an arbitrary object of user data. + :param auto_envvar_prefix: the prefix to use for automatic environment + variables. If this is `None` then reading + from environment variables is disabled. This + does not affect manually set environment + variables which are always read. + :param default_map: a dictionary (like object) with default values + for parameters. + :param terminal_width: the width of the terminal. The default is + inherit from parent context. If no context + defines the terminal width then auto + detection will be applied. + :param max_content_width: the maximum width for content rendered by + Click (this currently only affects help + pages). This defaults to 80 characters if + not overridden. In other words: even if the + terminal is larger than that, Click will not + format things wider than 80 characters by + default. In addition to that, formatters might + add some safety mapping on the right. + :param resilient_parsing: if this flag is enabled then Click will + parse without any interactivity or callback + invocation. This is useful for implementing + things such as completion support. + :param allow_extra_args: if this is set to `True` then extra arguments + at the end will not raise an error and will be + kept on the context. The default is to inherit + from the command. + :param allow_interspersed_args: if this is set to `False` then options + and arguments cannot be mixed. The + default is to inherit from the command. + :param ignore_unknown_options: instructs click to ignore options it does + not know and keeps them for later + processing. + :param help_option_names: optionally a list of strings that define how + the default help parameter is named. The + default is ``['--help']``. + :param token_normalize_func: an optional function that is used to + normalize tokens (options, choices, + etc.). This for instance can be used to + implement case insensitive behavior. + :param color: controls if the terminal supports ANSI colors or not. The + default is autodetection. This is only needed if ANSI + codes are used in texts that Click prints which is by + default not the case. This for instance would affect + help output. + """ + + def __init__(self, command, parent=None, info_name=None, obj=None, + auto_envvar_prefix=None, default_map=None, + terminal_width=None, max_content_width=None, + resilient_parsing=False, allow_extra_args=None, + allow_interspersed_args=None, + ignore_unknown_options=None, help_option_names=None, + token_normalize_func=None, color=None): + #: the parent context or `None` if none exists. + self.parent = parent + #: the :class:`Command` for this context. + self.command = command + #: the descriptive information name + self.info_name = info_name + #: the parsed parameters except if the value is hidden in which + #: case it's not remembered. + self.params = {} + #: the leftover arguments. + self.args = [] + #: protected arguments. These are arguments that are prepended + #: to `args` when certain parsing scenarios are encountered but + #: must be never propagated to another arguments. This is used + #: to implement nested parsing. + self.protected_args = [] + if obj is None and parent is not None: + obj = parent.obj + #: the user object stored. + self.obj = obj + self._meta = getattr(parent, 'meta', {}) + + #: A dictionary (-like object) with defaults for parameters. + if default_map is None \ + and parent is not None \ + and parent.default_map is not None: + default_map = parent.default_map.get(info_name) + self.default_map = default_map + + #: This flag indicates if a subcommand is going to be executed. A + #: group callback can use this information to figure out if it's + #: being executed directly or because the execution flow passes + #: onwards to a subcommand. By default it's None, but it can be + #: the name of the subcommand to execute. + #: + #: If chaining is enabled this will be set to ``'*'`` in case + #: any commands are executed. It is however not possible to + #: figure out which ones. If you require this knowledge you + #: should use a :func:`resultcallback`. + self.invoked_subcommand = None + + if terminal_width is None and parent is not None: + terminal_width = parent.terminal_width + #: The width of the terminal (None is autodetection). + self.terminal_width = terminal_width + + if max_content_width is None and parent is not None: + max_content_width = parent.max_content_width + #: The maximum width of formatted content (None implies a sensible + #: default which is 80 for most things). + self.max_content_width = max_content_width + + if allow_extra_args is None: + allow_extra_args = command.allow_extra_args + #: Indicates if the context allows extra args or if it should + #: fail on parsing. + #: + #: .. versionadded:: 3.0 + self.allow_extra_args = allow_extra_args + + if allow_interspersed_args is None: + allow_interspersed_args = command.allow_interspersed_args + #: Indicates if the context allows mixing of arguments and + #: options or not. + #: + #: .. versionadded:: 3.0 + self.allow_interspersed_args = allow_interspersed_args + + if ignore_unknown_options is None: + ignore_unknown_options = command.ignore_unknown_options + #: Instructs click to ignore options that a command does not + #: understand and will store it on the context for later + #: processing. This is primarily useful for situations where you + #: want to call into external programs. Generally this pattern is + #: strongly discouraged because it's not possibly to losslessly + #: forward all arguments. + #: + #: .. versionadded:: 4.0 + self.ignore_unknown_options = ignore_unknown_options + + if help_option_names is None: + if parent is not None: + help_option_names = parent.help_option_names + else: + help_option_names = ['--help'] + + #: The names for the help options. + self.help_option_names = help_option_names + + if token_normalize_func is None and parent is not None: + token_normalize_func = parent.token_normalize_func + + #: An optional normalization function for tokens. This is + #: options, choices, commands etc. + self.token_normalize_func = token_normalize_func + + #: Indicates if resilient parsing is enabled. In that case Click + #: will do its best to not cause any failures. + self.resilient_parsing = resilient_parsing + + # If there is no envvar prefix yet, but the parent has one and + # the command on this level has a name, we can expand the envvar + # prefix automatically. + if auto_envvar_prefix is None: + if parent is not None \ + and parent.auto_envvar_prefix is not None and \ + self.info_name is not None: + auto_envvar_prefix = '%s_%s' % (parent.auto_envvar_prefix, + self.info_name.upper()) + else: + self.auto_envvar_prefix = auto_envvar_prefix.upper() + self.auto_envvar_prefix = auto_envvar_prefix + + if color is None and parent is not None: + color = parent.color + + #: Controls if styling output is wanted or not. + self.color = color + + self._close_callbacks = [] + self._depth = 0 + + def __enter__(self): + self._depth += 1 + push_context(self) + return self + + def __exit__(self, exc_type, exc_value, tb): + self._depth -= 1 + if self._depth == 0: + self.close() + pop_context() + + @contextmanager + def scope(self, cleanup=True): + """This helper method can be used with the context object to promote + it to the current thread local (see :func:`get_current_context`). + The default behavior of this is to invoke the cleanup functions which + can be disabled by setting `cleanup` to `False`. The cleanup + functions are typically used for things such as closing file handles. + + If the cleanup is intended the context object can also be directly + used as a context manager. + + Example usage:: + + with ctx.scope(): + assert get_current_context() is ctx + + This is equivalent:: + + with ctx: + assert get_current_context() is ctx + + .. versionadded:: 5.0 + + :param cleanup: controls if the cleanup functions should be run or + not. The default is to run these functions. In + some situations the context only wants to be + temporarily pushed in which case this can be disabled. + Nested pushes automatically defer the cleanup. + """ + if not cleanup: + self._depth += 1 + try: + with self as rv: + yield rv + finally: + if not cleanup: + self._depth -= 1 + + @property + def meta(self): + """This is a dictionary which is shared with all the contexts + that are nested. It exists so that click utiltiies can store some + state here if they need to. It is however the responsibility of + that code to manage this dictionary well. + + The keys are supposed to be unique dotted strings. For instance + module paths are a good choice for it. What is stored in there is + irrelevant for the operation of click. However what is important is + that code that places data here adheres to the general semantics of + the system. + + Example usage:: + + LANG_KEY = __name__ + '.lang' + + def set_language(value): + ctx = get_current_context() + ctx.meta[LANG_KEY] = value + + def get_language(): + return get_current_context().meta.get(LANG_KEY, 'en_US') + + .. versionadded:: 5.0 + """ + return self._meta + + def make_formatter(self): + """Creates the formatter for the help and usage output.""" + return HelpFormatter(width=self.terminal_width, + max_width=self.max_content_width) + + def call_on_close(self, f): + """This decorator remembers a function as callback that should be + executed when the context tears down. This is most useful to bind + resource handling to the script execution. For instance, file objects + opened by the :class:`File` type will register their close callbacks + here. + + :param f: the function to execute on teardown. + """ + self._close_callbacks.append(f) + return f + + def close(self): + """Invokes all close callbacks.""" + for cb in self._close_callbacks: + cb() + self._close_callbacks = [] + + @property + def command_path(self): + """The computed command path. This is used for the ``usage`` + information on the help page. It's automatically created by + combining the info names of the chain of contexts to the root. + """ + rv = '' + if self.info_name is not None: + rv = self.info_name + if self.parent is not None: + rv = self.parent.command_path + ' ' + rv + return rv.lstrip() + + def find_root(self): + """Finds the outermost context.""" + node = self + while node.parent is not None: + node = node.parent + return node + + def find_object(self, object_type): + """Finds the closest object of a given type.""" + node = self + while node is not None: + if isinstance(node.obj, object_type): + return node.obj + node = node.parent + + def ensure_object(self, object_type): + """Like :meth:`find_object` but sets the innermost object to a + new instance of `object_type` if it does not exist. + """ + rv = self.find_object(object_type) + if rv is None: + self.obj = rv = object_type() + return rv + + def lookup_default(self, name): + """Looks up the default for a parameter name. This by default + looks into the :attr:`default_map` if available. + """ + if self.default_map is not None: + rv = self.default_map.get(name) + if callable(rv): + rv = rv() + return rv + + def fail(self, message): + """Aborts the execution of the program with a specific error + message. + + :param message: the error message to fail with. + """ + raise UsageError(message, self) + + def abort(self): + """Aborts the script.""" + raise Abort() + + def exit(self, code=0): + """Exits the application with a given exit code.""" + sys.exit(code) + + def get_usage(self): + """Helper method to get formatted usage string for the current + context and command. + """ + return self.command.get_usage(self) + + def get_help(self): + """Helper method to get formatted help page for the current + context and command. + """ + return self.command.get_help(self) + + def invoke(*args, **kwargs): + """Invokes a command callback in exactly the way it expects. There + are two ways to invoke this method: + + 1. the first argument can be a callback and all other arguments and + keyword arguments are forwarded directly to the function. + 2. the first argument is a click command object. In that case all + arguments are forwarded as well but proper click parameters + (options and click arguments) must be keyword arguments and Click + will fill in defaults. + + Note that before Click 3.2 keyword arguments were not properly filled + in against the intention of this code and no context was created. For + more information about this change and why it was done in a bugfix + release see :ref:`upgrade-to-3.2`. + """ + self, callback = args[:2] + ctx = self + + # It's also possible to invoke another command which might or + # might not have a callback. In that case we also fill + # in defaults and make a new context for this command. + if isinstance(callback, Command): + other_cmd = callback + callback = other_cmd.callback + ctx = Context(other_cmd, info_name=other_cmd.name, parent=self) + if callback is None: + raise TypeError('The given command does not have a ' + 'callback that can be invoked.') + + for param in other_cmd.params: + if param.name not in kwargs and param.expose_value: + kwargs[param.name] = param.get_default(ctx) + + args = args[2:] + with augment_usage_errors(self): + with ctx: + return callback(*args, **kwargs) + + def forward(*args, **kwargs): + """Similar to :meth:`invoke` but fills in default keyword + arguments from the current context if the other command expects + it. This cannot invoke callbacks directly, only other commands. + """ + self, cmd = args[:2] + + # It's also possible to invoke another command which might or + # might not have a callback. + if not isinstance(cmd, Command): + raise TypeError('Callback is not a command.') + + for param in self.params: + if param not in kwargs: + kwargs[param] = self.params[param] + + return self.invoke(cmd, **kwargs) + + +class BaseCommand(object): + """The base command implements the minimal API contract of commands. + Most code will never use this as it does not implement a lot of useful + functionality but it can act as the direct subclass of alternative + parsing methods that do not depend on the Click parser. + + For instance, this can be used to bridge Click and other systems like + argparse or docopt. + + Because base commands do not implement a lot of the API that other + parts of Click take for granted, they are not supported for all + operations. For instance, they cannot be used with the decorators + usually and they have no built-in callback system. + + .. versionchanged:: 2.0 + Added the `context_settings` parameter. + + :param name: the name of the command to use unless a group overrides it. + :param context_settings: an optional dictionary with defaults that are + passed to the context object. + """ + #: the default for the :attr:`Context.allow_extra_args` flag. + allow_extra_args = False + #: the default for the :attr:`Context.allow_interspersed_args` flag. + allow_interspersed_args = True + #: the default for the :attr:`Context.ignore_unknown_options` flag. + ignore_unknown_options = False + + def __init__(self, name, context_settings=None): + #: the name the command thinks it has. Upon registering a command + #: on a :class:`Group` the group will default the command name + #: with this information. You should instead use the + #: :class:`Context`\'s :attr:`~Context.info_name` attribute. + self.name = name + if context_settings is None: + context_settings = {} + #: an optional dictionary with defaults passed to the context. + self.context_settings = context_settings + + def get_usage(self, ctx): + raise NotImplementedError('Base commands cannot get usage') + + def get_help(self, ctx): + raise NotImplementedError('Base commands cannot get help') + + def make_context(self, info_name, args, parent=None, **extra): + """This function when given an info name and arguments will kick + off the parsing and create a new :class:`Context`. It does not + invoke the actual command callback though. + + :param info_name: the info name for this invokation. Generally this + is the most descriptive name for the script or + command. For the toplevel script it's usually + the name of the script, for commands below it it's + the name of the script. + :param args: the arguments to parse as list of strings. + :param parent: the parent context if available. + :param extra: extra keyword arguments forwarded to the context + constructor. + """ + for key, value in iteritems(self.context_settings): + if key not in extra: + extra[key] = value + ctx = Context(self, info_name=info_name, parent=parent, **extra) + with ctx.scope(cleanup=False): + self.parse_args(ctx, args) + return ctx + + def parse_args(self, ctx, args): + """Given a context and a list of arguments this creates the parser + and parses the arguments, then modifies the context as necessary. + This is automatically invoked by :meth:`make_context`. + """ + raise NotImplementedError('Base commands do not know how to parse ' + 'arguments.') + + def invoke(self, ctx): + """Given a context, this invokes the command. The default + implementation is raising a not implemented error. + """ + raise NotImplementedError('Base commands are not invokable by default') + + def main(self, args=None, prog_name=None, complete_var=None, + standalone_mode=True, **extra): + """This is the way to invoke a script with all the bells and + whistles as a command line application. This will always terminate + the application after a call. If this is not wanted, ``SystemExit`` + needs to be caught. + + This method is also available by directly calling the instance of + a :class:`Command`. + + .. versionadded:: 3.0 + Added the `standalone_mode` flag to control the standalone mode. + + :param args: the arguments that should be used for parsing. If not + provided, ``sys.argv[1:]`` is used. + :param prog_name: the program name that should be used. By default + the program name is constructed by taking the file + name from ``sys.argv[0]``. + :param complete_var: the environment variable that controls the + bash completion support. The default is + ``"__COMPLETE"`` with prog name in + uppercase. + :param standalone_mode: the default behavior is to invoke the script + in standalone mode. Click will then + handle exceptions and convert them into + error messages and the function will never + return but shut down the interpreter. If + this is set to `False` they will be + propagated to the caller and the return + value of this function is the return value + of :meth:`invoke`. + :param extra: extra keyword arguments are forwarded to the context + constructor. See :class:`Context` for more information. + """ + # If we are in Python 3, we will verify that the environment is + # sane at this point of reject further execution to avoid a + # broken script. + if not PY2: + _verify_python3_env() + else: + _check_for_unicode_literals() + + if args is None: + args = get_os_args() + else: + args = list(args) + + if prog_name is None: + prog_name = make_str(os.path.basename( + sys.argv and sys.argv[0] or __file__)) + + # Hook for the Bash completion. This only activates if the Bash + # completion is actually enabled, otherwise this is quite a fast + # noop. + _bashcomplete(self, prog_name, complete_var) + + try: + try: + with self.make_context(prog_name, args, **extra) as ctx: + rv = self.invoke(ctx) + if not standalone_mode: + return rv + ctx.exit() + except (EOFError, KeyboardInterrupt): + echo(file=sys.stderr) + raise Abort() + except ClickException as e: + if not standalone_mode: + raise + e.show() + sys.exit(e.exit_code) + except IOError as e: + if e.errno == errno.EPIPE: + sys.exit(1) + else: + raise + except Abort: + if not standalone_mode: + raise + echo('Aborted!', file=sys.stderr) + sys.exit(1) + + def __call__(self, *args, **kwargs): + """Alias for :meth:`main`.""" + return self.main(*args, **kwargs) + + +class Command(BaseCommand): + """Commands are the basic building block of command line interfaces in + Click. A basic command handles command line parsing and might dispatch + more parsing to commands nested below it. + + .. versionchanged:: 2.0 + Added the `context_settings` parameter. + + :param name: the name of the command to use unless a group overrides it. + :param context_settings: an optional dictionary with defaults that are + passed to the context object. + :param callback: the callback to invoke. This is optional. + :param params: the parameters to register with this command. This can + be either :class:`Option` or :class:`Argument` objects. + :param help: the help string to use for this command. + :param epilog: like the help string but it's printed at the end of the + help page after everything else. + :param short_help: the short help to use for this command. This is + shown on the command listing of the parent command. + :param add_help_option: by default each command registers a ``--help`` + option. This can be disabled by this parameter. + """ + + def __init__(self, name, context_settings=None, callback=None, + params=None, help=None, epilog=None, short_help=None, + options_metavar='[OPTIONS]', add_help_option=True): + BaseCommand.__init__(self, name, context_settings) + #: the callback to execute when the command fires. This might be + #: `None` in which case nothing happens. + self.callback = callback + #: the list of parameters for this command in the order they + #: should show up in the help page and execute. Eager parameters + #: will automatically be handled before non eager ones. + self.params = params or [] + self.help = help + self.epilog = epilog + self.options_metavar = options_metavar + if short_help is None and help: + short_help = make_default_short_help(help) + self.short_help = short_help + self.add_help_option = add_help_option + + def get_usage(self, ctx): + formatter = ctx.make_formatter() + self.format_usage(ctx, formatter) + return formatter.getvalue().rstrip('\n') + + def get_params(self, ctx): + rv = self.params + help_option = self.get_help_option(ctx) + if help_option is not None: + rv = rv + [help_option] + return rv + + def format_usage(self, ctx, formatter): + """Writes the usage line into the formatter.""" + pieces = self.collect_usage_pieces(ctx) + formatter.write_usage(ctx.command_path, ' '.join(pieces)) + + def collect_usage_pieces(self, ctx): + """Returns all the pieces that go into the usage line and returns + it as a list of strings. + """ + rv = [self.options_metavar] + for param in self.get_params(ctx): + rv.extend(param.get_usage_pieces(ctx)) + return rv + + def get_help_option_names(self, ctx): + """Returns the names for the help option.""" + all_names = set(ctx.help_option_names) + for param in self.params: + all_names.difference_update(param.opts) + all_names.difference_update(param.secondary_opts) + return all_names + + def get_help_option(self, ctx): + """Returns the help option object.""" + help_options = self.get_help_option_names(ctx) + if not help_options or not self.add_help_option: + return + + def show_help(ctx, param, value): + if value and not ctx.resilient_parsing: + echo(ctx.get_help(), color=ctx.color) + ctx.exit() + return Option(help_options, is_flag=True, + is_eager=True, expose_value=False, + callback=show_help, + help='Show this message and exit.') + + def make_parser(self, ctx): + """Creates the underlying option parser for this command.""" + parser = OptionParser(ctx) + parser.allow_interspersed_args = ctx.allow_interspersed_args + parser.ignore_unknown_options = ctx.ignore_unknown_options + for param in self.get_params(ctx): + param.add_to_parser(parser, ctx) + return parser + + def get_help(self, ctx): + """Formats the help into a string and returns it. This creates a + formatter and will call into the following formatting methods: + """ + formatter = ctx.make_formatter() + self.format_help(ctx, formatter) + return formatter.getvalue().rstrip('\n') + + def format_help(self, ctx, formatter): + """Writes the help into the formatter if it exists. + + This calls into the following methods: + + - :meth:`format_usage` + - :meth:`format_help_text` + - :meth:`format_options` + - :meth:`format_epilog` + """ + self.format_usage(ctx, formatter) + self.format_help_text(ctx, formatter) + self.format_options(ctx, formatter) + self.format_epilog(ctx, formatter) + + def format_help_text(self, ctx, formatter): + """Writes the help text to the formatter if it exists.""" + if self.help: + formatter.write_paragraph() + with formatter.indentation(): + formatter.write_text(self.help) + + def format_options(self, ctx, formatter): + """Writes all the options into the formatter if they exist.""" + opts = [] + for param in self.get_params(ctx): + rv = param.get_help_record(ctx) + if rv is not None: + opts.append(rv) + + if opts: + with formatter.section('Options'): + formatter.write_dl(opts) + + def format_epilog(self, ctx, formatter): + """Writes the epilog into the formatter if it exists.""" + if self.epilog: + formatter.write_paragraph() + with formatter.indentation(): + formatter.write_text(self.epilog) + + def parse_args(self, ctx, args): + parser = self.make_parser(ctx) + opts, args, param_order = parser.parse_args(args=args) + + for param in iter_params_for_processing( + param_order, self.get_params(ctx)): + value, args = param.handle_parse_result(ctx, opts, args) + + if args and not ctx.allow_extra_args and not ctx.resilient_parsing: + ctx.fail('Got unexpected extra argument%s (%s)' + % (len(args) != 1 and 's' or '', + ' '.join(map(make_str, args)))) + + ctx.args = args + return args + + def invoke(self, ctx): + """Given a context, this invokes the attached callback (if it exists) + in the right way. + """ + if self.callback is not None: + return ctx.invoke(self.callback, **ctx.params) + + +class MultiCommand(Command): + """A multi command is the basic implementation of a command that + dispatches to subcommands. The most common version is the + :class:`Group`. + + :param invoke_without_command: this controls how the multi command itself + is invoked. By default it's only invoked + if a subcommand is provided. + :param no_args_is_help: this controls what happens if no arguments are + provided. This option is enabled by default if + `invoke_without_command` is disabled or disabled + if it's enabled. If enabled this will add + ``--help`` as argument if no arguments are + passed. + :param subcommand_metavar: the string that is used in the documentation + to indicate the subcommand place. + :param chain: if this is set to `True` chaining of multiple subcommands + is enabled. This restricts the form of commands in that + they cannot have optional arguments but it allows + multiple commands to be chained together. + :param result_callback: the result callback to attach to this multi + command. + """ + allow_extra_args = True + allow_interspersed_args = False + + def __init__(self, name=None, invoke_without_command=False, + no_args_is_help=None, subcommand_metavar=None, + chain=False, result_callback=None, **attrs): + Command.__init__(self, name, **attrs) + if no_args_is_help is None: + no_args_is_help = not invoke_without_command + self.no_args_is_help = no_args_is_help + self.invoke_without_command = invoke_without_command + if subcommand_metavar is None: + if chain: + subcommand_metavar = SUBCOMMANDS_METAVAR + else: + subcommand_metavar = SUBCOMMAND_METAVAR + self.subcommand_metavar = subcommand_metavar + self.chain = chain + #: The result callback that is stored. This can be set or + #: overridden with the :func:`resultcallback` decorator. + self.result_callback = result_callback + + if self.chain: + for param in self.params: + if isinstance(param, Argument) and not param.required: + raise RuntimeError('Multi commands in chain mode cannot ' + 'have optional arguments.') + + def collect_usage_pieces(self, ctx): + rv = Command.collect_usage_pieces(self, ctx) + rv.append(self.subcommand_metavar) + return rv + + def format_options(self, ctx, formatter): + Command.format_options(self, ctx, formatter) + self.format_commands(ctx, formatter) + + def resultcallback(self, replace=False): + """Adds a result callback to the chain command. By default if a + result callback is already registered this will chain them but + this can be disabled with the `replace` parameter. The result + callback is invoked with the return value of the subcommand + (or the list of return values from all subcommands if chaining + is enabled) as well as the parameters as they would be passed + to the main callback. + + Example:: + + @click.group() + @click.option('-i', '--input', default=23) + def cli(input): + return 42 + + @cli.resultcallback() + def process_result(result, input): + return result + input + + .. versionadded:: 3.0 + + :param replace: if set to `True` an already existing result + callback will be removed. + """ + def decorator(f): + old_callback = self.result_callback + if old_callback is None or replace: + self.result_callback = f + return f + def function(__value, *args, **kwargs): + return f(old_callback(__value, *args, **kwargs), + *args, **kwargs) + self.result_callback = rv = update_wrapper(function, f) + return rv + return decorator + + def format_commands(self, ctx, formatter): + """Extra format methods for multi methods that adds all the commands + after the options. + """ + rows = [] + for subcommand in self.list_commands(ctx): + cmd = self.get_command(ctx, subcommand) + # What is this, the tool lied about a command. Ignore it + if cmd is None: + continue + + help = cmd.short_help or '' + rows.append((subcommand, help)) + + if rows: + with formatter.section('Commands'): + formatter.write_dl(rows) + + def parse_args(self, ctx, args): + if not args and self.no_args_is_help and not ctx.resilient_parsing: + echo(ctx.get_help(), color=ctx.color) + ctx.exit() + + rest = Command.parse_args(self, ctx, args) + if self.chain: + ctx.protected_args = rest + ctx.args = [] + elif rest: + ctx.protected_args, ctx.args = rest[:1], rest[1:] + + return ctx.args + + def invoke(self, ctx): + def _process_result(value): + if self.result_callback is not None: + value = ctx.invoke(self.result_callback, value, + **ctx.params) + return value + + if not ctx.protected_args: + # If we are invoked without command the chain flag controls + # how this happens. If we are not in chain mode, the return + # value here is the return value of the command. + # If however we are in chain mode, the return value is the + # return value of the result processor invoked with an empty + # list (which means that no subcommand actually was executed). + if self.invoke_without_command: + if not self.chain: + return Command.invoke(self, ctx) + with ctx: + Command.invoke(self, ctx) + return _process_result([]) + ctx.fail('Missing command.') + + # Fetch args back out + args = ctx.protected_args + ctx.args + ctx.args = [] + ctx.protected_args = [] + + # If we're not in chain mode, we only allow the invocation of a + # single command but we also inform the current context about the + # name of the command to invoke. + if not self.chain: + # Make sure the context is entered so we do not clean up + # resources until the result processor has worked. + with ctx: + cmd_name, cmd, args = self.resolve_command(ctx, args) + ctx.invoked_subcommand = cmd_name + Command.invoke(self, ctx) + sub_ctx = cmd.make_context(cmd_name, args, parent=ctx) + with sub_ctx: + return _process_result(sub_ctx.command.invoke(sub_ctx)) + + # In chain mode we create the contexts step by step, but after the + # base command has been invoked. Because at that point we do not + # know the subcommands yet, the invoked subcommand attribute is + # set to ``*`` to inform the command that subcommands are executed + # but nothing else. + with ctx: + ctx.invoked_subcommand = args and '*' or None + Command.invoke(self, ctx) + + # Otherwise we make every single context and invoke them in a + # chain. In that case the return value to the result processor + # is the list of all invoked subcommand's results. + contexts = [] + while args: + cmd_name, cmd, args = self.resolve_command(ctx, args) + sub_ctx = cmd.make_context(cmd_name, args, parent=ctx, + allow_extra_args=True, + allow_interspersed_args=False) + contexts.append(sub_ctx) + args, sub_ctx.args = sub_ctx.args, [] + + rv = [] + for sub_ctx in contexts: + with sub_ctx: + rv.append(sub_ctx.command.invoke(sub_ctx)) + return _process_result(rv) + + def resolve_command(self, ctx, args): + cmd_name = make_str(args[0]) + original_cmd_name = cmd_name + + # Get the command + cmd = self.get_command(ctx, cmd_name) + + # If we can't find the command but there is a normalization + # function available, we try with that one. + if cmd is None and ctx.token_normalize_func is not None: + cmd_name = ctx.token_normalize_func(cmd_name) + cmd = self.get_command(ctx, cmd_name) + + # If we don't find the command we want to show an error message + # to the user that it was not provided. However, there is + # something else we should do: if the first argument looks like + # an option we want to kick off parsing again for arguments to + # resolve things like --help which now should go to the main + # place. + if cmd is None: + if split_opt(cmd_name)[0]: + self.parse_args(ctx, ctx.args) + ctx.fail('No such command "%s".' % original_cmd_name) + + return cmd_name, cmd, args[1:] + + def get_command(self, ctx, cmd_name): + """Given a context and a command name, this returns a + :class:`Command` object if it exists or returns `None`. + """ + raise NotImplementedError() + + def list_commands(self, ctx): + """Returns a list of subcommand names in the order they should + appear. + """ + return [] + + +class Group(MultiCommand): + """A group allows a command to have subcommands attached. This is the + most common way to implement nesting in Click. + + :param commands: a dictionary of commands. + """ + + def __init__(self, name=None, commands=None, **attrs): + MultiCommand.__init__(self, name, **attrs) + #: the registered subcommands by their exported names. + self.commands = commands or {} + + def add_command(self, cmd, name=None): + """Registers another :class:`Command` with this group. If the name + is not provided, the name of the command is used. + """ + name = name or cmd.name + if name is None: + raise TypeError('Command has no name.') + _check_multicommand(self, name, cmd, register=True) + self.commands[name] = cmd + + def command(self, *args, **kwargs): + """A shortcut decorator for declaring and attaching a command to + the group. This takes the same arguments as :func:`command` but + immediately registers the created command with this instance by + calling into :meth:`add_command`. + """ + def decorator(f): + cmd = command(*args, **kwargs)(f) + self.add_command(cmd) + return cmd + return decorator + + def group(self, *args, **kwargs): + """A shortcut decorator for declaring and attaching a group to + the group. This takes the same arguments as :func:`group` but + immediately registers the created command with this instance by + calling into :meth:`add_command`. + """ + def decorator(f): + cmd = group(*args, **kwargs)(f) + self.add_command(cmd) + return cmd + return decorator + + def get_command(self, ctx, cmd_name): + return self.commands.get(cmd_name) + + def list_commands(self, ctx): + return sorted(self.commands) + + +class CommandCollection(MultiCommand): + """A command collection is a multi command that merges multiple multi + commands together into one. This is a straightforward implementation + that accepts a list of different multi commands as sources and + provides all the commands for each of them. + """ + + def __init__(self, name=None, sources=None, **attrs): + MultiCommand.__init__(self, name, **attrs) + #: The list of registered multi commands. + self.sources = sources or [] + + def add_source(self, multi_cmd): + """Adds a new multi command to the chain dispatcher.""" + self.sources.append(multi_cmd) + + def get_command(self, ctx, cmd_name): + for source in self.sources: + rv = source.get_command(ctx, cmd_name) + if rv is not None: + if self.chain: + _check_multicommand(self, cmd_name, rv) + return rv + + def list_commands(self, ctx): + rv = set() + for source in self.sources: + rv.update(source.list_commands(ctx)) + return sorted(rv) + + +class Parameter(object): + """A parameter to a command comes in two versions: they are either + :class:`Option`\s or :class:`Argument`\s. Other subclasses are currently + not supported by design as some of the internals for parsing are + intentionally not finalized. + + Some settings are supported by both options and arguments. + + .. versionchanged:: 2.0 + Changed signature for parameter callback to also be passed the + parameter. In Click 2.0, the old callback format will still work, + but it will raise a warning to give you change to migrate the + code easier. + + :param param_decls: the parameter declarations for this option or + argument. This is a list of flags or argument + names. + :param type: the type that should be used. Either a :class:`ParamType` + or a Python type. The later is converted into the former + automatically if supported. + :param required: controls if this is optional or not. + :param default: the default value if omitted. This can also be a callable, + in which case it's invoked when the default is needed + without any arguments. + :param callback: a callback that should be executed after the parameter + was matched. This is called as ``fn(ctx, param, + value)`` and needs to return the value. Before Click + 2.0, the signature was ``(ctx, value)``. + :param nargs: the number of arguments to match. If not ``1`` the return + value is a tuple instead of single value. The default for + nargs is ``1`` (except if the type is a tuple, then it's + the arity of the tuple). + :param metavar: how the value is represented in the help page. + :param expose_value: if this is `True` then the value is passed onwards + to the command callback and stored on the context, + otherwise it's skipped. + :param is_eager: eager values are processed before non eager ones. This + should not be set for arguments or it will inverse the + order of processing. + :param envvar: a string or list of strings that are environment variables + that should be checked. + """ + param_type_name = 'parameter' + + def __init__(self, param_decls=None, type=None, required=False, + default=None, callback=None, nargs=None, metavar=None, + expose_value=True, is_eager=False, envvar=None): + self.name, self.opts, self.secondary_opts = \ + self._parse_decls(param_decls or (), expose_value) + + self.type = convert_type(type, default) + + # Default nargs to what the type tells us if we have that + # information available. + if nargs is None: + if self.type.is_composite: + nargs = self.type.arity + else: + nargs = 1 + + self.required = required + self.callback = callback + self.nargs = nargs + self.multiple = False + self.expose_value = expose_value + self.default = default + self.is_eager = is_eager + self.metavar = metavar + self.envvar = envvar + + @property + def human_readable_name(self): + """Returns the human readable name of this parameter. This is the + same as the name for options, but the metavar for arguments. + """ + return self.name + + def make_metavar(self): + if self.metavar is not None: + return self.metavar + metavar = self.type.get_metavar(self) + if metavar is None: + metavar = self.type.name.upper() + if self.nargs != 1: + metavar += '...' + return metavar + + def get_default(self, ctx): + """Given a context variable this calculates the default value.""" + # Otherwise go with the regular default. + if callable(self.default): + rv = self.default() + else: + rv = self.default + return self.type_cast_value(ctx, rv) + + def add_to_parser(self, parser, ctx): + pass + + def consume_value(self, ctx, opts): + value = opts.get(self.name) + if value is None: + value = ctx.lookup_default(self.name) + if value is None: + value = self.value_from_envvar(ctx) + return value + + def type_cast_value(self, ctx, value): + """Given a value this runs it properly through the type system. + This automatically handles things like `nargs` and `multiple` as + well as composite types. + """ + if self.type.is_composite: + if self.nargs <= 1: + raise TypeError('Attempted to invoke composite type ' + 'but nargs has been set to %s. This is ' + 'not supported; nargs needs to be set to ' + 'a fixed value > 1.' % self.nargs) + if self.multiple: + return tuple(self.type(x or (), self, ctx) for x in value or ()) + return self.type(value or (), self, ctx) + + def _convert(value, level): + if level == 0: + return self.type(value, self, ctx) + return tuple(_convert(x, level - 1) for x in value or ()) + return _convert(value, (self.nargs != 1) + bool(self.multiple)) + + def process_value(self, ctx, value): + """Given a value and context this runs the logic to convert the + value as necessary. + """ + # If the value we were given is None we do nothing. This way + # code that calls this can easily figure out if something was + # not provided. Otherwise it would be converted into an empty + # tuple for multiple invocations which is inconvenient. + if value is not None: + return self.type_cast_value(ctx, value) + + def value_is_missing(self, value): + if value is None: + return True + if (self.nargs != 1 or self.multiple) and value == (): + return True + return False + + def full_process_value(self, ctx, value): + value = self.process_value(ctx, value) + + if value is None: + value = self.get_default(ctx) + + if self.required and self.value_is_missing(value): + raise MissingParameter(ctx=ctx, param=self) + + return value + + def resolve_envvar_value(self, ctx): + if self.envvar is None: + return + if isinstance(self.envvar, (tuple, list)): + for envvar in self.envvar: + rv = os.environ.get(envvar) + if rv is not None: + return rv + else: + return os.environ.get(self.envvar) + + def value_from_envvar(self, ctx): + rv = self.resolve_envvar_value(ctx) + if rv is not None and self.nargs != 1: + rv = self.type.split_envvar_value(rv) + return rv + + def handle_parse_result(self, ctx, opts, args): + with augment_usage_errors(ctx, param=self): + value = self.consume_value(ctx, opts) + try: + value = self.full_process_value(ctx, value) + except Exception: + if not ctx.resilient_parsing: + raise + value = None + if self.callback is not None: + try: + value = invoke_param_callback( + self.callback, ctx, self, value) + except Exception: + if not ctx.resilient_parsing: + raise + + if self.expose_value: + ctx.params[self.name] = value + return value, args + + def get_help_record(self, ctx): + pass + + def get_usage_pieces(self, ctx): + return [] + + +class Option(Parameter): + """Options are usually optional values on the command line and + have some extra features that arguments don't have. + + All other parameters are passed onwards to the parameter constructor. + + :param show_default: controls if the default value should be shown on the + help page. Normally, defaults are not shown. + :param prompt: if set to `True` or a non empty string then the user will + be prompted for input if not set. If set to `True` the + prompt will be the option name capitalized. + :param confirmation_prompt: if set then the value will need to be confirmed + if it was prompted for. + :param hide_input: if this is `True` then the input on the prompt will be + hidden from the user. This is useful for password + input. + :param is_flag: forces this option to act as a flag. The default is + auto detection. + :param flag_value: which value should be used for this flag if it's + enabled. This is set to a boolean automatically if + the option string contains a slash to mark two options. + :param multiple: if this is set to `True` then the argument is accepted + multiple times and recorded. This is similar to ``nargs`` + in how it works but supports arbitrary number of + arguments. + :param count: this flag makes an option increment an integer. + :param allow_from_autoenv: if this is enabled then the value of this + parameter will be pulled from an environment + variable in case a prefix is defined on the + context. + :param help: the help string. + """ + param_type_name = 'option' + + def __init__(self, param_decls=None, show_default=False, + prompt=False, confirmation_prompt=False, + hide_input=False, is_flag=None, flag_value=None, + multiple=False, count=False, allow_from_autoenv=True, + type=None, help=None, **attrs): + default_is_missing = attrs.get('default', _missing) is _missing + Parameter.__init__(self, param_decls, type=type, **attrs) + + if prompt is True: + prompt_text = self.name.replace('_', ' ').capitalize() + elif prompt is False: + prompt_text = None + else: + prompt_text = prompt + self.prompt = prompt_text + self.confirmation_prompt = confirmation_prompt + self.hide_input = hide_input + + # Flags + if is_flag is None: + if flag_value is not None: + is_flag = True + else: + is_flag = bool(self.secondary_opts) + if is_flag and default_is_missing: + self.default = False + if flag_value is None: + flag_value = not self.default + self.is_flag = is_flag + self.flag_value = flag_value + if self.is_flag and isinstance(self.flag_value, bool) \ + and type is None: + self.type = BOOL + self.is_bool_flag = True + else: + self.is_bool_flag = False + + # Counting + self.count = count + if count: + if type is None: + self.type = IntRange(min=0) + if default_is_missing: + self.default = 0 + + self.multiple = multiple + self.allow_from_autoenv = allow_from_autoenv + self.help = help + self.show_default = show_default + + # Sanity check for stuff we don't support + if __debug__: + if self.nargs < 0: + raise TypeError('Options cannot have nargs < 0') + if self.prompt and self.is_flag and not self.is_bool_flag: + raise TypeError('Cannot prompt for flags that are not bools.') + if not self.is_bool_flag and self.secondary_opts: + raise TypeError('Got secondary option for non boolean flag.') + if self.is_bool_flag and self.hide_input \ + and self.prompt is not None: + raise TypeError('Hidden input does not work with boolean ' + 'flag prompts.') + if self.count: + if self.multiple: + raise TypeError('Options cannot be multiple and count ' + 'at the same time.') + elif self.is_flag: + raise TypeError('Options cannot be count and flags at ' + 'the same time.') + + def _parse_decls(self, decls, expose_value): + opts = [] + secondary_opts = [] + name = None + possible_names = [] + + for decl in decls: + if isidentifier(decl): + if name is not None: + raise TypeError('Name defined twice') + name = decl + else: + split_char = decl[:1] == '/' and ';' or '/' + if split_char in decl: + first, second = decl.split(split_char, 1) + first = first.rstrip() + if first: + possible_names.append(split_opt(first)) + opts.append(first) + second = second.lstrip() + if second: + secondary_opts.append(second.lstrip()) + else: + possible_names.append(split_opt(decl)) + opts.append(decl) + + if name is None and possible_names: + possible_names.sort(key=lambda x: len(x[0])) + name = possible_names[-1][1].replace('-', '_').lower() + if not isidentifier(name): + name = None + + if name is None: + if not expose_value: + return None, opts, secondary_opts + raise TypeError('Could not determine name for option') + + if not opts and not secondary_opts: + raise TypeError('No options defined but a name was passed (%s). ' + 'Did you mean to declare an argument instead ' + 'of an option?' % name) + + return name, opts, secondary_opts + + def add_to_parser(self, parser, ctx): + kwargs = { + 'dest': self.name, + 'nargs': self.nargs, + 'obj': self, + } + + if self.multiple: + action = 'append' + elif self.count: + action = 'count' + else: + action = 'store' + + if self.is_flag: + kwargs.pop('nargs', None) + if self.is_bool_flag and self.secondary_opts: + parser.add_option(self.opts, action=action + '_const', + const=True, **kwargs) + parser.add_option(self.secondary_opts, action=action + + '_const', const=False, **kwargs) + else: + parser.add_option(self.opts, action=action + '_const', + const=self.flag_value, + **kwargs) + else: + kwargs['action'] = action + parser.add_option(self.opts, **kwargs) + + def get_help_record(self, ctx): + any_prefix_is_slash = [] + + def _write_opts(opts): + rv, any_slashes = join_options(opts) + if any_slashes: + any_prefix_is_slash[:] = [True] + if not self.is_flag and not self.count: + rv += ' ' + self.make_metavar() + return rv + + rv = [_write_opts(self.opts)] + if self.secondary_opts: + rv.append(_write_opts(self.secondary_opts)) + + help = self.help or '' + extra = [] + if self.default is not None and self.show_default: + extra.append('default: %s' % ( + ', '.join('%s' % d for d in self.default) + if isinstance(self.default, (list, tuple)) + else self.default, )) + if self.required: + extra.append('required') + if extra: + help = '%s[%s]' % (help and help + ' ' or '', '; '.join(extra)) + + return ((any_prefix_is_slash and '; ' or ' / ').join(rv), help) + + def get_default(self, ctx): + # If we're a non boolean flag out default is more complex because + # we need to look at all flags in the same group to figure out + # if we're the the default one in which case we return the flag + # value as default. + if self.is_flag and not self.is_bool_flag: + for param in ctx.command.params: + if param.name == self.name and param.default: + return param.flag_value + return None + return Parameter.get_default(self, ctx) + + def prompt_for_value(self, ctx): + """This is an alternative flow that can be activated in the full + value processing if a value does not exist. It will prompt the + user until a valid value exists and then returns the processed + value as result. + """ + # Calculate the default before prompting anything to be stable. + default = self.get_default(ctx) + + # If this is a prompt for a flag we need to handle this + # differently. + if self.is_bool_flag: + return confirm(self.prompt, default) + + return prompt(self.prompt, default=default, + hide_input=self.hide_input, + confirmation_prompt=self.confirmation_prompt, + value_proc=lambda x: self.process_value(ctx, x)) + + def resolve_envvar_value(self, ctx): + rv = Parameter.resolve_envvar_value(self, ctx) + if rv is not None: + return rv + if self.allow_from_autoenv and \ + ctx.auto_envvar_prefix is not None: + envvar = '%s_%s' % (ctx.auto_envvar_prefix, self.name.upper()) + return os.environ.get(envvar) + + def value_from_envvar(self, ctx): + rv = self.resolve_envvar_value(ctx) + if rv is None: + return None + value_depth = (self.nargs != 1) + bool(self.multiple) + if value_depth > 0 and rv is not None: + rv = self.type.split_envvar_value(rv) + if self.multiple and self.nargs != 1: + rv = batch(rv, self.nargs) + return rv + + def full_process_value(self, ctx, value): + if value is None and self.prompt is not None \ + and not ctx.resilient_parsing: + return self.prompt_for_value(ctx) + return Parameter.full_process_value(self, ctx, value) + + +class Argument(Parameter): + """Arguments are positional parameters to a command. They generally + provide fewer features than options but can have infinite ``nargs`` + and are required by default. + + All parameters are passed onwards to the parameter constructor. + """ + param_type_name = 'argument' + + def __init__(self, param_decls, required=None, **attrs): + if required is None: + if attrs.get('default') is not None: + required = False + else: + required = attrs.get('nargs', 1) > 0 + Parameter.__init__(self, param_decls, required=required, **attrs) + if self.default is not None and self.nargs < 0: + raise TypeError('nargs=-1 in combination with a default value ' + 'is not supported.') + + @property + def human_readable_name(self): + if self.metavar is not None: + return self.metavar + return self.name.upper() + + def make_metavar(self): + if self.metavar is not None: + return self.metavar + var = self.name.upper() + if not self.required: + var = '[%s]' % var + if self.nargs != 1: + var += '...' + return var + + def _parse_decls(self, decls, expose_value): + if not decls: + if not expose_value: + return None, [], [] + raise TypeError('Could not determine name for argument') + if len(decls) == 1: + name = arg = decls[0] + name = name.replace('-', '_').lower() + elif len(decls) == 2: + name, arg = decls + else: + raise TypeError('Arguments take exactly one or two ' + 'parameter declarations, got %d' % len(decls)) + return name, [arg], [] + + def get_usage_pieces(self, ctx): + return [self.make_metavar()] + + def add_to_parser(self, parser, ctx): + parser.add_argument(dest=self.name, nargs=self.nargs, + obj=self) + + +# Circular dependency between decorators and core +from .decorators import command, group diff --git a/pyextra/click/decorators.py b/pyextra/click/decorators.py new file mode 100644 index 00000000000000..9893452650ba0a --- /dev/null +++ b/pyextra/click/decorators.py @@ -0,0 +1,304 @@ +import sys +import inspect + +from functools import update_wrapper + +from ._compat import iteritems +from ._unicodefun import _check_for_unicode_literals +from .utils import echo +from .globals import get_current_context + + +def pass_context(f): + """Marks a callback as wanting to receive the current context + object as first argument. + """ + def new_func(*args, **kwargs): + return f(get_current_context(), *args, **kwargs) + return update_wrapper(new_func, f) + + +def pass_obj(f): + """Similar to :func:`pass_context`, but only pass the object on the + context onwards (:attr:`Context.obj`). This is useful if that object + represents the state of a nested system. + """ + def new_func(*args, **kwargs): + return f(get_current_context().obj, *args, **kwargs) + return update_wrapper(new_func, f) + + +def make_pass_decorator(object_type, ensure=False): + """Given an object type this creates a decorator that will work + similar to :func:`pass_obj` but instead of passing the object of the + current context, it will find the innermost context of type + :func:`object_type`. + + This generates a decorator that works roughly like this:: + + from functools import update_wrapper + + def decorator(f): + @pass_context + def new_func(ctx, *args, **kwargs): + obj = ctx.find_object(object_type) + return ctx.invoke(f, obj, *args, **kwargs) + return update_wrapper(new_func, f) + return decorator + + :param object_type: the type of the object to pass. + :param ensure: if set to `True`, a new object will be created and + remembered on the context if it's not there yet. + """ + def decorator(f): + def new_func(*args, **kwargs): + ctx = get_current_context() + if ensure: + obj = ctx.ensure_object(object_type) + else: + obj = ctx.find_object(object_type) + if obj is None: + raise RuntimeError('Managed to invoke callback without a ' + 'context object of type %r existing' + % object_type.__name__) + return ctx.invoke(f, obj, *args[1:], **kwargs) + return update_wrapper(new_func, f) + return decorator + + +def _make_command(f, name, attrs, cls): + if isinstance(f, Command): + raise TypeError('Attempted to convert a callback into a ' + 'command twice.') + try: + params = f.__click_params__ + params.reverse() + del f.__click_params__ + except AttributeError: + params = [] + help = attrs.get('help') + if help is None: + help = inspect.getdoc(f) + if isinstance(help, bytes): + help = help.decode('utf-8') + else: + help = inspect.cleandoc(help) + attrs['help'] = help + _check_for_unicode_literals() + return cls(name=name or f.__name__.lower(), + callback=f, params=params, **attrs) + + +def command(name=None, cls=None, **attrs): + """Creates a new :class:`Command` and uses the decorated function as + callback. This will also automatically attach all decorated + :func:`option`\s and :func:`argument`\s as parameters to the command. + + The name of the command defaults to the name of the function. If you + want to change that, you can pass the intended name as the first + argument. + + All keyword arguments are forwarded to the underlying command class. + + Once decorated the function turns into a :class:`Command` instance + that can be invoked as a command line utility or be attached to a + command :class:`Group`. + + :param name: the name of the command. This defaults to the function + name. + :param cls: the command class to instantiate. This defaults to + :class:`Command`. + """ + if cls is None: + cls = Command + def decorator(f): + cmd = _make_command(f, name, attrs, cls) + cmd.__doc__ = f.__doc__ + return cmd + return decorator + + +def group(name=None, **attrs): + """Creates a new :class:`Group` with a function as callback. This + works otherwise the same as :func:`command` just that the `cls` + parameter is set to :class:`Group`. + """ + attrs.setdefault('cls', Group) + return command(name, **attrs) + + +def _param_memo(f, param): + if isinstance(f, Command): + f.params.append(param) + else: + if not hasattr(f, '__click_params__'): + f.__click_params__ = [] + f.__click_params__.append(param) + + +def argument(*param_decls, **attrs): + """Attaches an argument to the command. All positional arguments are + passed as parameter declarations to :class:`Argument`; all keyword + arguments are forwarded unchanged (except ``cls``). + This is equivalent to creating an :class:`Argument` instance manually + and attaching it to the :attr:`Command.params` list. + + :param cls: the argument class to instantiate. This defaults to + :class:`Argument`. + """ + def decorator(f): + ArgumentClass = attrs.pop('cls', Argument) + _param_memo(f, ArgumentClass(param_decls, **attrs)) + return f + return decorator + + +def option(*param_decls, **attrs): + """Attaches an option to the command. All positional arguments are + passed as parameter declarations to :class:`Option`; all keyword + arguments are forwarded unchanged (except ``cls``). + This is equivalent to creating an :class:`Option` instance manually + and attaching it to the :attr:`Command.params` list. + + :param cls: the option class to instantiate. This defaults to + :class:`Option`. + """ + def decorator(f): + if 'help' in attrs: + attrs['help'] = inspect.cleandoc(attrs['help']) + OptionClass = attrs.pop('cls', Option) + _param_memo(f, OptionClass(param_decls, **attrs)) + return f + return decorator + + +def confirmation_option(*param_decls, **attrs): + """Shortcut for confirmation prompts that can be ignored by passing + ``--yes`` as parameter. + + This is equivalent to decorating a function with :func:`option` with + the following parameters:: + + def callback(ctx, param, value): + if not value: + ctx.abort() + + @click.command() + @click.option('--yes', is_flag=True, callback=callback, + expose_value=False, prompt='Do you want to continue?') + def dropdb(): + pass + """ + def decorator(f): + def callback(ctx, param, value): + if not value: + ctx.abort() + attrs.setdefault('is_flag', True) + attrs.setdefault('callback', callback) + attrs.setdefault('expose_value', False) + attrs.setdefault('prompt', 'Do you want to continue?') + attrs.setdefault('help', 'Confirm the action without prompting.') + return option(*(param_decls or ('--yes',)), **attrs)(f) + return decorator + + +def password_option(*param_decls, **attrs): + """Shortcut for password prompts. + + This is equivalent to decorating a function with :func:`option` with + the following parameters:: + + @click.command() + @click.option('--password', prompt=True, confirmation_prompt=True, + hide_input=True) + def changeadmin(password): + pass + """ + def decorator(f): + attrs.setdefault('prompt', True) + attrs.setdefault('confirmation_prompt', True) + attrs.setdefault('hide_input', True) + return option(*(param_decls or ('--password',)), **attrs)(f) + return decorator + + +def version_option(version=None, *param_decls, **attrs): + """Adds a ``--version`` option which immediately ends the program + printing out the version number. This is implemented as an eager + option that prints the version and exits the program in the callback. + + :param version: the version number to show. If not provided Click + attempts an auto discovery via setuptools. + :param prog_name: the name of the program (defaults to autodetection) + :param message: custom message to show instead of the default + (``'%(prog)s, version %(version)s'``) + :param others: everything else is forwarded to :func:`option`. + """ + if version is None: + module = sys._getframe(1).f_globals.get('__name__') + def decorator(f): + prog_name = attrs.pop('prog_name', None) + message = attrs.pop('message', '%(prog)s, version %(version)s') + + def callback(ctx, param, value): + if not value or ctx.resilient_parsing: + return + prog = prog_name + if prog is None: + prog = ctx.find_root().info_name + ver = version + if ver is None: + try: + import pkg_resources + except ImportError: + pass + else: + for dist in pkg_resources.working_set: + scripts = dist.get_entry_map().get('console_scripts') or {} + for script_name, entry_point in iteritems(scripts): + if entry_point.module_name == module: + ver = dist.version + break + if ver is None: + raise RuntimeError('Could not determine version') + echo(message % { + 'prog': prog, + 'version': ver, + }, color=ctx.color) + ctx.exit() + + attrs.setdefault('is_flag', True) + attrs.setdefault('expose_value', False) + attrs.setdefault('is_eager', True) + attrs.setdefault('help', 'Show the version and exit.') + attrs['callback'] = callback + return option(*(param_decls or ('--version',)), **attrs)(f) + return decorator + + +def help_option(*param_decls, **attrs): + """Adds a ``--help`` option which immediately ends the program + printing out the help page. This is usually unnecessary to add as + this is added by default to all commands unless suppressed. + + Like :func:`version_option`, this is implemented as eager option that + prints in the callback and exits. + + All arguments are forwarded to :func:`option`. + """ + def decorator(f): + def callback(ctx, param, value): + if value and not ctx.resilient_parsing: + echo(ctx.get_help(), color=ctx.color) + ctx.exit() + attrs.setdefault('is_flag', True) + attrs.setdefault('expose_value', False) + attrs.setdefault('help', 'Show this message and exit.') + attrs.setdefault('is_eager', True) + attrs['callback'] = callback + return option(*(param_decls or ('--help',)), **attrs)(f) + return decorator + + +# Circular dependencies between core and decorators +from .core import Command, Group, Argument, Option diff --git a/pyextra/click/exceptions.py b/pyextra/click/exceptions.py new file mode 100644 index 00000000000000..74a4542bb57f29 --- /dev/null +++ b/pyextra/click/exceptions.py @@ -0,0 +1,201 @@ +from ._compat import PY2, filename_to_ui, get_text_stderr +from .utils import echo + + +class ClickException(Exception): + """An exception that Click can handle and show to the user.""" + + #: The exit code for this exception + exit_code = 1 + + def __init__(self, message): + if PY2: + if message is not None: + message = message.encode('utf-8') + Exception.__init__(self, message) + self.message = message + + def format_message(self): + return self.message + + def show(self, file=None): + if file is None: + file = get_text_stderr() + echo('Error: %s' % self.format_message(), file=file) + + +class UsageError(ClickException): + """An internal exception that signals a usage error. This typically + aborts any further handling. + + :param message: the error message to display. + :param ctx: optionally the context that caused this error. Click will + fill in the context automatically in some situations. + """ + exit_code = 2 + + def __init__(self, message, ctx=None): + ClickException.__init__(self, message) + self.ctx = ctx + + def show(self, file=None): + if file is None: + file = get_text_stderr() + color = None + if self.ctx is not None: + color = self.ctx.color + echo(self.ctx.get_usage() + '\n', file=file, color=color) + echo('Error: %s' % self.format_message(), file=file, color=color) + + +class BadParameter(UsageError): + """An exception that formats out a standardized error message for a + bad parameter. This is useful when thrown from a callback or type as + Click will attach contextual information to it (for instance, which + parameter it is). + + .. versionadded:: 2.0 + + :param param: the parameter object that caused this error. This can + be left out, and Click will attach this info itself + if possible. + :param param_hint: a string that shows up as parameter name. This + can be used as alternative to `param` in cases + where custom validation should happen. If it is + a string it's used as such, if it's a list then + each item is quoted and separated. + """ + + def __init__(self, message, ctx=None, param=None, + param_hint=None): + UsageError.__init__(self, message, ctx) + self.param = param + self.param_hint = param_hint + + def format_message(self): + if self.param_hint is not None: + param_hint = self.param_hint + elif self.param is not None: + param_hint = self.param.opts or [self.param.human_readable_name] + else: + return 'Invalid value: %s' % self.message + if isinstance(param_hint, (tuple, list)): + param_hint = ' / '.join('"%s"' % x for x in param_hint) + return 'Invalid value for %s: %s' % (param_hint, self.message) + + +class MissingParameter(BadParameter): + """Raised if click required an option or argument but it was not + provided when invoking the script. + + .. versionadded:: 4.0 + + :param param_type: a string that indicates the type of the parameter. + The default is to inherit the parameter type from + the given `param`. Valid values are ``'parameter'``, + ``'option'`` or ``'argument'``. + """ + + def __init__(self, message=None, ctx=None, param=None, + param_hint=None, param_type=None): + BadParameter.__init__(self, message, ctx, param, param_hint) + self.param_type = param_type + + def format_message(self): + if self.param_hint is not None: + param_hint = self.param_hint + elif self.param is not None: + param_hint = self.param.opts or [self.param.human_readable_name] + else: + param_hint = None + if isinstance(param_hint, (tuple, list)): + param_hint = ' / '.join('"%s"' % x for x in param_hint) + + param_type = self.param_type + if param_type is None and self.param is not None: + param_type = self.param.param_type_name + + msg = self.message + if self.param is not None: + msg_extra = self.param.type.get_missing_message(self.param) + if msg_extra: + if msg: + msg += '. ' + msg_extra + else: + msg = msg_extra + + return 'Missing %s%s%s%s' % ( + param_type, + param_hint and ' %s' % param_hint or '', + msg and '. ' or '.', + msg or '', + ) + + +class NoSuchOption(UsageError): + """Raised if click attempted to handle an option that does not + exist. + + .. versionadded:: 4.0 + """ + + def __init__(self, option_name, message=None, possibilities=None, + ctx=None): + if message is None: + message = 'no such option: %s' % option_name + UsageError.__init__(self, message, ctx) + self.option_name = option_name + self.possibilities = possibilities + + def format_message(self): + bits = [self.message] + if self.possibilities: + if len(self.possibilities) == 1: + bits.append('Did you mean %s?' % self.possibilities[0]) + else: + possibilities = sorted(self.possibilities) + bits.append('(Possible options: %s)' % ', '.join(possibilities)) + return ' '.join(bits) + + +class BadOptionUsage(UsageError): + """Raised if an option is generally supplied but the use of the option + was incorrect. This is for instance raised if the number of arguments + for an option is not correct. + + .. versionadded:: 4.0 + """ + + def __init__(self, message, ctx=None): + UsageError.__init__(self, message, ctx) + + +class BadArgumentUsage(UsageError): + """Raised if an argument is generally supplied but the use of the argument + was incorrect. This is for instance raised if the number of values + for an argument is not correct. + + .. versionadded:: 6.0 + """ + + def __init__(self, message, ctx=None): + UsageError.__init__(self, message, ctx) + + +class FileError(ClickException): + """Raised if a file cannot be opened.""" + + def __init__(self, filename, hint=None): + ui_filename = filename_to_ui(filename) + if hint is None: + hint = 'unknown error' + ClickException.__init__(self, hint) + self.ui_filename = ui_filename + self.filename = filename + + def format_message(self): + return 'Could not open file %s: %s' % (self.ui_filename, self.message) + + +class Abort(RuntimeError): + """An internal signalling exception that signals Click to abort.""" diff --git a/pyextra/click/formatting.py b/pyextra/click/formatting.py new file mode 100644 index 00000000000000..a3d6a4d389019c --- /dev/null +++ b/pyextra/click/formatting.py @@ -0,0 +1,256 @@ +from contextlib import contextmanager +from .termui import get_terminal_size +from .parser import split_opt +from ._compat import term_len + + +# Can force a width. This is used by the test system +FORCED_WIDTH = None + + +def measure_table(rows): + widths = {} + for row in rows: + for idx, col in enumerate(row): + widths[idx] = max(widths.get(idx, 0), term_len(col)) + return tuple(y for x, y in sorted(widths.items())) + + +def iter_rows(rows, col_count): + for row in rows: + row = tuple(row) + yield row + ('',) * (col_count - len(row)) + + +def wrap_text(text, width=78, initial_indent='', subsequent_indent='', + preserve_paragraphs=False): + """A helper function that intelligently wraps text. By default, it + assumes that it operates on a single paragraph of text but if the + `preserve_paragraphs` parameter is provided it will intelligently + handle paragraphs (defined by two empty lines). + + If paragraphs are handled, a paragraph can be prefixed with an empty + line containing the ``\\b`` character (``\\x08``) to indicate that + no rewrapping should happen in that block. + + :param text: the text that should be rewrapped. + :param width: the maximum width for the text. + :param initial_indent: the initial indent that should be placed on the + first line as a string. + :param subsequent_indent: the indent string that should be placed on + each consecutive line. + :param preserve_paragraphs: if this flag is set then the wrapping will + intelligently handle paragraphs. + """ + from ._textwrap import TextWrapper + text = text.expandtabs() + wrapper = TextWrapper(width, initial_indent=initial_indent, + subsequent_indent=subsequent_indent, + replace_whitespace=False) + if not preserve_paragraphs: + return wrapper.fill(text) + + p = [] + buf = [] + indent = None + + def _flush_par(): + if not buf: + return + if buf[0].strip() == '\b': + p.append((indent or 0, True, '\n'.join(buf[1:]))) + else: + p.append((indent or 0, False, ' '.join(buf))) + del buf[:] + + for line in text.splitlines(): + if not line: + _flush_par() + indent = None + else: + if indent is None: + orig_len = term_len(line) + line = line.lstrip() + indent = orig_len - term_len(line) + buf.append(line) + _flush_par() + + rv = [] + for indent, raw, text in p: + with wrapper.extra_indent(' ' * indent): + if raw: + rv.append(wrapper.indent_only(text)) + else: + rv.append(wrapper.fill(text)) + + return '\n\n'.join(rv) + + +class HelpFormatter(object): + """This class helps with formatting text-based help pages. It's + usually just needed for very special internal cases, but it's also + exposed so that developers can write their own fancy outputs. + + At present, it always writes into memory. + + :param indent_increment: the additional increment for each level. + :param width: the width for the text. This defaults to the terminal + width clamped to a maximum of 78. + """ + + def __init__(self, indent_increment=2, width=None, max_width=None): + self.indent_increment = indent_increment + if max_width is None: + max_width = 80 + if width is None: + width = FORCED_WIDTH + if width is None: + width = max(min(get_terminal_size()[0], max_width) - 2, 50) + self.width = width + self.current_indent = 0 + self.buffer = [] + + def write(self, string): + """Writes a unicode string into the internal buffer.""" + self.buffer.append(string) + + def indent(self): + """Increases the indentation.""" + self.current_indent += self.indent_increment + + def dedent(self): + """Decreases the indentation.""" + self.current_indent -= self.indent_increment + + def write_usage(self, prog, args='', prefix='Usage: '): + """Writes a usage line into the buffer. + + :param prog: the program name. + :param args: whitespace separated list of arguments. + :param prefix: the prefix for the first line. + """ + usage_prefix = '%*s%s ' % (self.current_indent, prefix, prog) + text_width = self.width - self.current_indent + + if text_width >= (term_len(usage_prefix) + 20): + # The arguments will fit to the right of the prefix. + indent = ' ' * term_len(usage_prefix) + self.write(wrap_text(args, text_width, + initial_indent=usage_prefix, + subsequent_indent=indent)) + else: + # The prefix is too long, put the arguments on the next line. + self.write(usage_prefix) + self.write('\n') + indent = ' ' * (max(self.current_indent, term_len(prefix)) + 4) + self.write(wrap_text(args, text_width, + initial_indent=indent, + subsequent_indent=indent)) + + self.write('\n') + + def write_heading(self, heading): + """Writes a heading into the buffer.""" + self.write('%*s%s:\n' % (self.current_indent, '', heading)) + + def write_paragraph(self): + """Writes a paragraph into the buffer.""" + if self.buffer: + self.write('\n') + + def write_text(self, text): + """Writes re-indented text into the buffer. This rewraps and + preserves paragraphs. + """ + text_width = max(self.width - self.current_indent, 11) + indent = ' ' * self.current_indent + self.write(wrap_text(text, text_width, + initial_indent=indent, + subsequent_indent=indent, + preserve_paragraphs=True)) + self.write('\n') + + def write_dl(self, rows, col_max=30, col_spacing=2): + """Writes a definition list into the buffer. This is how options + and commands are usually formatted. + + :param rows: a list of two item tuples for the terms and values. + :param col_max: the maximum width of the first column. + :param col_spacing: the number of spaces between the first and + second column. + """ + rows = list(rows) + widths = measure_table(rows) + if len(widths) != 2: + raise TypeError('Expected two columns for definition list') + + first_col = min(widths[0], col_max) + col_spacing + + for first, second in iter_rows(rows, len(widths)): + self.write('%*s%s' % (self.current_indent, '', first)) + if not second: + self.write('\n') + continue + if term_len(first) <= first_col - col_spacing: + self.write(' ' * (first_col - term_len(first))) + else: + self.write('\n') + self.write(' ' * (first_col + self.current_indent)) + + text_width = max(self.width - first_col - 2, 10) + lines = iter(wrap_text(second, text_width).splitlines()) + if lines: + self.write(next(lines) + '\n') + for line in lines: + self.write('%*s%s\n' % ( + first_col + self.current_indent, '', line)) + else: + self.write('\n') + + @contextmanager + def section(self, name): + """Helpful context manager that writes a paragraph, a heading, + and the indents. + + :param name: the section name that is written as heading. + """ + self.write_paragraph() + self.write_heading(name) + self.indent() + try: + yield + finally: + self.dedent() + + @contextmanager + def indentation(self): + """A context manager that increases the indentation.""" + self.indent() + try: + yield + finally: + self.dedent() + + def getvalue(self): + """Returns the buffer contents.""" + return ''.join(self.buffer) + + +def join_options(options): + """Given a list of option strings this joins them in the most appropriate + way and returns them in the form ``(formatted_string, + any_prefix_is_slash)`` where the second item in the tuple is a flag that + indicates if any of the option prefixes was a slash. + """ + rv = [] + any_prefix_is_slash = False + for opt in options: + prefix = split_opt(opt)[0] + if prefix == '/': + any_prefix_is_slash = True + rv.append((len(prefix), opt)) + + rv.sort(key=lambda x: x[0]) + + rv = ', '.join(x[1] for x in rv) + return rv, any_prefix_is_slash diff --git a/pyextra/click/globals.py b/pyextra/click/globals.py new file mode 100644 index 00000000000000..14338e6bb8434b --- /dev/null +++ b/pyextra/click/globals.py @@ -0,0 +1,48 @@ +from threading import local + + +_local = local() + + +def get_current_context(silent=False): + """Returns the current click context. This can be used as a way to + access the current context object from anywhere. This is a more implicit + alternative to the :func:`pass_context` decorator. This function is + primarily useful for helpers such as :func:`echo` which might be + interested in changing it's behavior based on the current context. + + To push the current context, :meth:`Context.scope` can be used. + + .. versionadded:: 5.0 + + :param silent: is set to `True` the return value is `None` if no context + is available. The default behavior is to raise a + :exc:`RuntimeError`. + """ + try: + return getattr(_local, 'stack')[-1] + except (AttributeError, IndexError): + if not silent: + raise RuntimeError('There is no active click context.') + + +def push_context(ctx): + """Pushes a new context to the current stack.""" + _local.__dict__.setdefault('stack', []).append(ctx) + + +def pop_context(): + """Removes the top level from the stack.""" + _local.stack.pop() + + +def resolve_color_default(color=None): + """"Internal helper to get the default value of the color flag. If a + value is passed it's returned unchanged, otherwise it's looked up from + the current context. + """ + if color is not None: + return color + ctx = get_current_context(silent=True) + if ctx is not None: + return ctx.color diff --git a/pyextra/click/parser.py b/pyextra/click/parser.py new file mode 100644 index 00000000000000..9775c9ff9b99d8 --- /dev/null +++ b/pyextra/click/parser.py @@ -0,0 +1,426 @@ +# -*- coding: utf-8 -*- +""" + click.parser + ~~~~~~~~~~~~ + + This module started out as largely a copy paste from the stdlib's + optparse module with the features removed that we do not need from + optparse because we implement them in Click on a higher level (for + instance type handling, help formatting and a lot more). + + The plan is to remove more and more from here over time. + + The reason this is a different module and not optparse from the stdlib + is that there are differences in 2.x and 3.x about the error messages + generated and optparse in the stdlib uses gettext for no good reason + and might cause us issues. +""" +import re +from collections import deque +from .exceptions import UsageError, NoSuchOption, BadOptionUsage, \ + BadArgumentUsage + + +def _unpack_args(args, nargs_spec): + """Given an iterable of arguments and an iterable of nargs specifications, + it returns a tuple with all the unpacked arguments at the first index + and all remaining arguments as the second. + + The nargs specification is the number of arguments that should be consumed + or `-1` to indicate that this position should eat up all the remainders. + + Missing items are filled with `None`. + """ + args = deque(args) + nargs_spec = deque(nargs_spec) + rv = [] + spos = None + + def _fetch(c): + try: + if spos is None: + return c.popleft() + else: + return c.pop() + except IndexError: + return None + + while nargs_spec: + nargs = _fetch(nargs_spec) + if nargs == 1: + rv.append(_fetch(args)) + elif nargs > 1: + x = [_fetch(args) for _ in range(nargs)] + # If we're reversed, we're pulling in the arguments in reverse, + # so we need to turn them around. + if spos is not None: + x.reverse() + rv.append(tuple(x)) + elif nargs < 0: + if spos is not None: + raise TypeError('Cannot have two nargs < 0') + spos = len(rv) + rv.append(None) + + # spos is the position of the wildcard (star). If it's not `None`, + # we fill it with the remainder. + if spos is not None: + rv[spos] = tuple(args) + args = [] + rv[spos + 1:] = reversed(rv[spos + 1:]) + + return tuple(rv), list(args) + + +def _error_opt_args(nargs, opt): + if nargs == 1: + raise BadOptionUsage('%s option requires an argument' % opt) + raise BadOptionUsage('%s option requires %d arguments' % (opt, nargs)) + + +def split_opt(opt): + first = opt[:1] + if first.isalnum(): + return '', opt + if opt[1:2] == first: + return opt[:2], opt[2:] + return first, opt[1:] + + +def normalize_opt(opt, ctx): + if ctx is None or ctx.token_normalize_func is None: + return opt + prefix, opt = split_opt(opt) + return prefix + ctx.token_normalize_func(opt) + + +def split_arg_string(string): + """Given an argument string this attempts to split it into small parts.""" + rv = [] + for match in re.finditer(r"('([^'\\]*(?:\\.[^'\\]*)*)'" + r'|"([^"\\]*(?:\\.[^"\\]*)*)"' + r'|\S+)\s*', string, re.S): + arg = match.group().strip() + if arg[:1] == arg[-1:] and arg[:1] in '"\'': + arg = arg[1:-1].encode('ascii', 'backslashreplace') \ + .decode('unicode-escape') + try: + arg = type(string)(arg) + except UnicodeError: + pass + rv.append(arg) + return rv + + +class Option(object): + + def __init__(self, opts, dest, action=None, nargs=1, const=None, obj=None): + self._short_opts = [] + self._long_opts = [] + self.prefixes = set() + + for opt in opts: + prefix, value = split_opt(opt) + if not prefix: + raise ValueError('Invalid start character for option (%s)' + % opt) + self.prefixes.add(prefix[0]) + if len(prefix) == 1 and len(value) == 1: + self._short_opts.append(opt) + else: + self._long_opts.append(opt) + self.prefixes.add(prefix) + + if action is None: + action = 'store' + + self.dest = dest + self.action = action + self.nargs = nargs + self.const = const + self.obj = obj + + @property + def takes_value(self): + return self.action in ('store', 'append') + + def process(self, value, state): + if self.action == 'store': + state.opts[self.dest] = value + elif self.action == 'store_const': + state.opts[self.dest] = self.const + elif self.action == 'append': + state.opts.setdefault(self.dest, []).append(value) + elif self.action == 'append_const': + state.opts.setdefault(self.dest, []).append(self.const) + elif self.action == 'count': + state.opts[self.dest] = state.opts.get(self.dest, 0) + 1 + else: + raise ValueError('unknown action %r' % self.action) + state.order.append(self.obj) + + +class Argument(object): + + def __init__(self, dest, nargs=1, obj=None): + self.dest = dest + self.nargs = nargs + self.obj = obj + + def process(self, value, state): + if self.nargs > 1: + holes = sum(1 for x in value if x is None) + if holes == len(value): + value = None + elif holes != 0: + raise BadArgumentUsage('argument %s takes %d values' + % (self.dest, self.nargs)) + state.opts[self.dest] = value + state.order.append(self.obj) + + +class ParsingState(object): + + def __init__(self, rargs): + self.opts = {} + self.largs = [] + self.rargs = rargs + self.order = [] + + +class OptionParser(object): + """The option parser is an internal class that is ultimately used to + parse options and arguments. It's modelled after optparse and brings + a similar but vastly simplified API. It should generally not be used + directly as the high level Click classes wrap it for you. + + It's not nearly as extensible as optparse or argparse as it does not + implement features that are implemented on a higher level (such as + types or defaults). + + :param ctx: optionally the :class:`~click.Context` where this parser + should go with. + """ + + def __init__(self, ctx=None): + #: The :class:`~click.Context` for this parser. This might be + #: `None` for some advanced use cases. + self.ctx = ctx + #: This controls how the parser deals with interspersed arguments. + #: If this is set to `False`, the parser will stop on the first + #: non-option. Click uses this to implement nested subcommands + #: safely. + self.allow_interspersed_args = True + #: This tells the parser how to deal with unknown options. By + #: default it will error out (which is sensible), but there is a + #: second mode where it will ignore it and continue processing + #: after shifting all the unknown options into the resulting args. + self.ignore_unknown_options = False + if ctx is not None: + self.allow_interspersed_args = ctx.allow_interspersed_args + self.ignore_unknown_options = ctx.ignore_unknown_options + self._short_opt = {} + self._long_opt = {} + self._opt_prefixes = set(['-', '--']) + self._args = [] + + def add_option(self, opts, dest, action=None, nargs=1, const=None, + obj=None): + """Adds a new option named `dest` to the parser. The destination + is not inferred (unlike with optparse) and needs to be explicitly + provided. Action can be any of ``store``, ``store_const``, + ``append``, ``appnd_const`` or ``count``. + + The `obj` can be used to identify the option in the order list + that is returned from the parser. + """ + if obj is None: + obj = dest + opts = [normalize_opt(opt, self.ctx) for opt in opts] + option = Option(opts, dest, action=action, nargs=nargs, + const=const, obj=obj) + self._opt_prefixes.update(option.prefixes) + for opt in option._short_opts: + self._short_opt[opt] = option + for opt in option._long_opts: + self._long_opt[opt] = option + + def add_argument(self, dest, nargs=1, obj=None): + """Adds a positional argument named `dest` to the parser. + + The `obj` can be used to identify the option in the order list + that is returned from the parser. + """ + if obj is None: + obj = dest + self._args.append(Argument(dest=dest, nargs=nargs, obj=obj)) + + def parse_args(self, args): + """Parses positional arguments and returns ``(values, args, order)`` + for the parsed options and arguments as well as the leftover + arguments if there are any. The order is a list of objects as they + appear on the command line. If arguments appear multiple times they + will be memorized multiple times as well. + """ + state = ParsingState(args) + try: + self._process_args_for_options(state) + self._process_args_for_args(state) + except UsageError: + if self.ctx is None or not self.ctx.resilient_parsing: + raise + return state.opts, state.largs, state.order + + def _process_args_for_args(self, state): + pargs, args = _unpack_args(state.largs + state.rargs, + [x.nargs for x in self._args]) + + for idx, arg in enumerate(self._args): + arg.process(pargs[idx], state) + + state.largs = args + state.rargs = [] + + def _process_args_for_options(self, state): + while state.rargs: + arg = state.rargs.pop(0) + arglen = len(arg) + # Double dashes always handled explicitly regardless of what + # prefixes are valid. + if arg == '--': + return + elif arg[:1] in self._opt_prefixes and arglen > 1: + self._process_opts(arg, state) + elif self.allow_interspersed_args: + state.largs.append(arg) + else: + state.rargs.insert(0, arg) + return + + # Say this is the original argument list: + # [arg0, arg1, ..., arg(i-1), arg(i), arg(i+1), ..., arg(N-1)] + # ^ + # (we are about to process arg(i)). + # + # Then rargs is [arg(i), ..., arg(N-1)] and largs is a *subset* of + # [arg0, ..., arg(i-1)] (any options and their arguments will have + # been removed from largs). + # + # The while loop will usually consume 1 or more arguments per pass. + # If it consumes 1 (eg. arg is an option that takes no arguments), + # then after _process_arg() is done the situation is: + # + # largs = subset of [arg0, ..., arg(i)] + # rargs = [arg(i+1), ..., arg(N-1)] + # + # If allow_interspersed_args is false, largs will always be + # *empty* -- still a subset of [arg0, ..., arg(i-1)], but + # not a very interesting subset! + + def _match_long_opt(self, opt, explicit_value, state): + if opt not in self._long_opt: + possibilities = [word for word in self._long_opt + if word.startswith(opt)] + raise NoSuchOption(opt, possibilities=possibilities) + + option = self._long_opt[opt] + if option.takes_value: + # At this point it's safe to modify rargs by injecting the + # explicit value, because no exception is raised in this + # branch. This means that the inserted value will be fully + # consumed. + if explicit_value is not None: + state.rargs.insert(0, explicit_value) + + nargs = option.nargs + if len(state.rargs) < nargs: + _error_opt_args(nargs, opt) + elif nargs == 1: + value = state.rargs.pop(0) + else: + value = tuple(state.rargs[:nargs]) + del state.rargs[:nargs] + + elif explicit_value is not None: + raise BadOptionUsage('%s option does not take a value' % opt) + + else: + value = None + + option.process(value, state) + + def _match_short_opt(self, arg, state): + stop = False + i = 1 + prefix = arg[0] + unknown_options = [] + + for ch in arg[1:]: + opt = normalize_opt(prefix + ch, self.ctx) + option = self._short_opt.get(opt) + i += 1 + + if not option: + if self.ignore_unknown_options: + unknown_options.append(ch) + continue + raise NoSuchOption(opt) + if option.takes_value: + # Any characters left in arg? Pretend they're the + # next arg, and stop consuming characters of arg. + if i < len(arg): + state.rargs.insert(0, arg[i:]) + stop = True + + nargs = option.nargs + if len(state.rargs) < nargs: + _error_opt_args(nargs, opt) + elif nargs == 1: + value = state.rargs.pop(0) + else: + value = tuple(state.rargs[:nargs]) + del state.rargs[:nargs] + + else: + value = None + + option.process(value, state) + + if stop: + break + + # If we got any unknown options we re-combinate the string of the + # remaining options and re-attach the prefix, then report that + # to the state as new larg. This way there is basic combinatorics + # that can be achieved while still ignoring unknown arguments. + if self.ignore_unknown_options and unknown_options: + state.largs.append(prefix + ''.join(unknown_options)) + + def _process_opts(self, arg, state): + explicit_value = None + # Long option handling happens in two parts. The first part is + # supporting explicitly attached values. In any case, we will try + # to long match the option first. + if '=' in arg: + long_opt, explicit_value = arg.split('=', 1) + else: + long_opt = arg + norm_long_opt = normalize_opt(long_opt, self.ctx) + + # At this point we will match the (assumed) long option through + # the long option matching code. Note that this allows options + # like "-foo" to be matched as long options. + try: + self._match_long_opt(norm_long_opt, explicit_value, state) + except NoSuchOption: + # At this point the long option matching failed, and we need + # to try with short options. However there is a special rule + # which says, that if we have a two character options prefix + # (applies to "--foo" for instance), we do not dispatch to the + # short option code and will instead raise the no option + # error. + if arg[:2] not in self._opt_prefixes: + return self._match_short_opt(arg, state) + if not self.ignore_unknown_options: + raise + state.largs.append(arg) diff --git a/pyextra/click/termui.py b/pyextra/click/termui.py new file mode 100644 index 00000000000000..d9fba52325f35b --- /dev/null +++ b/pyextra/click/termui.py @@ -0,0 +1,539 @@ +import os +import sys +import struct + +from ._compat import raw_input, text_type, string_types, \ + isatty, strip_ansi, get_winterm_size, DEFAULT_COLUMNS, WIN +from .utils import echo +from .exceptions import Abort, UsageError +from .types import convert_type +from .globals import resolve_color_default + + +# The prompt functions to use. The doc tools currently override these +# functions to customize how they work. +visible_prompt_func = raw_input + +_ansi_colors = ('black', 'red', 'green', 'yellow', 'blue', 'magenta', + 'cyan', 'white', 'reset') +_ansi_reset_all = '\033[0m' + + +def hidden_prompt_func(prompt): + import getpass + return getpass.getpass(prompt) + + +def _build_prompt(text, suffix, show_default=False, default=None): + prompt = text + if default is not None and show_default: + prompt = '%s [%s]' % (prompt, default) + return prompt + suffix + + +def prompt(text, default=None, hide_input=False, + confirmation_prompt=False, type=None, + value_proc=None, prompt_suffix=': ', + show_default=True, err=False): + """Prompts a user for input. This is a convenience function that can + be used to prompt a user for input later. + + If the user aborts the input by sending a interrupt signal, this + function will catch it and raise a :exc:`Abort` exception. + + .. versionadded:: 6.0 + Added unicode support for cmd.exe on Windows. + + .. versionadded:: 4.0 + Added the `err` parameter. + + :param text: the text to show for the prompt. + :param default: the default value to use if no input happens. If this + is not given it will prompt until it's aborted. + :param hide_input: if this is set to true then the input value will + be hidden. + :param confirmation_prompt: asks for confirmation for the value. + :param type: the type to use to check the value against. + :param value_proc: if this parameter is provided it's a function that + is invoked instead of the type conversion to + convert a value. + :param prompt_suffix: a suffix that should be added to the prompt. + :param show_default: shows or hides the default value in the prompt. + :param err: if set to true the file defaults to ``stderr`` instead of + ``stdout``, the same as with echo. + """ + result = None + + def prompt_func(text): + f = hide_input and hidden_prompt_func or visible_prompt_func + try: + # Write the prompt separately so that we get nice + # coloring through colorama on Windows + echo(text, nl=False, err=err) + return f('') + except (KeyboardInterrupt, EOFError): + # getpass doesn't print a newline if the user aborts input with ^C. + # Allegedly this behavior is inherited from getpass(3). + # A doc bug has been filed at https://bugs.python.org/issue24711 + if hide_input: + echo(None, err=err) + raise Abort() + + if value_proc is None: + value_proc = convert_type(type, default) + + prompt = _build_prompt(text, prompt_suffix, show_default, default) + + while 1: + while 1: + value = prompt_func(prompt) + if value: + break + # If a default is set and used, then the confirmation + # prompt is always skipped because that's the only thing + # that really makes sense. + elif default is not None: + return default + try: + result = value_proc(value) + except UsageError as e: + echo('Error: %s' % e.message, err=err) + continue + if not confirmation_prompt: + return result + while 1: + value2 = prompt_func('Repeat for confirmation: ') + if value2: + break + if value == value2: + return result + echo('Error: the two entered values do not match', err=err) + + +def confirm(text, default=False, abort=False, prompt_suffix=': ', + show_default=True, err=False): + """Prompts for confirmation (yes/no question). + + If the user aborts the input by sending a interrupt signal this + function will catch it and raise a :exc:`Abort` exception. + + .. versionadded:: 4.0 + Added the `err` parameter. + + :param text: the question to ask. + :param default: the default for the prompt. + :param abort: if this is set to `True` a negative answer aborts the + exception by raising :exc:`Abort`. + :param prompt_suffix: a suffix that should be added to the prompt. + :param show_default: shows or hides the default value in the prompt. + :param err: if set to true the file defaults to ``stderr`` instead of + ``stdout``, the same as with echo. + """ + prompt = _build_prompt(text, prompt_suffix, show_default, + default and 'Y/n' or 'y/N') + while 1: + try: + # Write the prompt separately so that we get nice + # coloring through colorama on Windows + echo(prompt, nl=False, err=err) + value = visible_prompt_func('').lower().strip() + except (KeyboardInterrupt, EOFError): + raise Abort() + if value in ('y', 'yes'): + rv = True + elif value in ('n', 'no'): + rv = False + elif value == '': + rv = default + else: + echo('Error: invalid input', err=err) + continue + break + if abort and not rv: + raise Abort() + return rv + + +def get_terminal_size(): + """Returns the current size of the terminal as tuple in the form + ``(width, height)`` in columns and rows. + """ + # If shutil has get_terminal_size() (Python 3.3 and later) use that + if sys.version_info >= (3, 3): + import shutil + shutil_get_terminal_size = getattr(shutil, 'get_terminal_size', None) + if shutil_get_terminal_size: + sz = shutil_get_terminal_size() + return sz.columns, sz.lines + + if get_winterm_size is not None: + return get_winterm_size() + + def ioctl_gwinsz(fd): + try: + import fcntl + import termios + cr = struct.unpack( + 'hh', fcntl.ioctl(fd, termios.TIOCGWINSZ, '1234')) + except Exception: + return + return cr + + cr = ioctl_gwinsz(0) or ioctl_gwinsz(1) or ioctl_gwinsz(2) + if not cr: + try: + fd = os.open(os.ctermid(), os.O_RDONLY) + try: + cr = ioctl_gwinsz(fd) + finally: + os.close(fd) + except Exception: + pass + if not cr or not cr[0] or not cr[1]: + cr = (os.environ.get('LINES', 25), + os.environ.get('COLUMNS', DEFAULT_COLUMNS)) + return int(cr[1]), int(cr[0]) + + +def echo_via_pager(text, color=None): + """This function takes a text and shows it via an environment specific + pager on stdout. + + .. versionchanged:: 3.0 + Added the `color` flag. + + :param text: the text to page. + :param color: controls if the pager supports ANSI colors or not. The + default is autodetection. + """ + color = resolve_color_default(color) + if not isinstance(text, string_types): + text = text_type(text) + from ._termui_impl import pager + return pager(text + '\n', color) + + +def progressbar(iterable=None, length=None, label=None, show_eta=True, + show_percent=None, show_pos=False, + item_show_func=None, fill_char='#', empty_char='-', + bar_template='%(label)s [%(bar)s] %(info)s', + info_sep=' ', width=36, file=None, color=None): + """This function creates an iterable context manager that can be used + to iterate over something while showing a progress bar. It will + either iterate over the `iterable` or `length` items (that are counted + up). While iteration happens, this function will print a rendered + progress bar to the given `file` (defaults to stdout) and will attempt + to calculate remaining time and more. By default, this progress bar + will not be rendered if the file is not a terminal. + + The context manager creates the progress bar. When the context + manager is entered the progress bar is already displayed. With every + iteration over the progress bar, the iterable passed to the bar is + advanced and the bar is updated. When the context manager exits, + a newline is printed and the progress bar is finalized on screen. + + No printing must happen or the progress bar will be unintentionally + destroyed. + + Example usage:: + + with progressbar(items) as bar: + for item in bar: + do_something_with(item) + + Alternatively, if no iterable is specified, one can manually update the + progress bar through the `update()` method instead of directly + iterating over the progress bar. The update method accepts the number + of steps to increment the bar with:: + + with progressbar(length=chunks.total_bytes) as bar: + for chunk in chunks: + process_chunk(chunk) + bar.update(chunks.bytes) + + .. versionadded:: 2.0 + + .. versionadded:: 4.0 + Added the `color` parameter. Added a `update` method to the + progressbar object. + + :param iterable: an iterable to iterate over. If not provided the length + is required. + :param length: the number of items to iterate over. By default the + progressbar will attempt to ask the iterator about its + length, which might or might not work. If an iterable is + also provided this parameter can be used to override the + length. If an iterable is not provided the progress bar + will iterate over a range of that length. + :param label: the label to show next to the progress bar. + :param show_eta: enables or disables the estimated time display. This is + automatically disabled if the length cannot be + determined. + :param show_percent: enables or disables the percentage display. The + default is `True` if the iterable has a length or + `False` if not. + :param show_pos: enables or disables the absolute position display. The + default is `False`. + :param item_show_func: a function called with the current item which + can return a string to show the current item + next to the progress bar. Note that the current + item can be `None`! + :param fill_char: the character to use to show the filled part of the + progress bar. + :param empty_char: the character to use to show the non-filled part of + the progress bar. + :param bar_template: the format string to use as template for the bar. + The parameters in it are ``label`` for the label, + ``bar`` for the progress bar and ``info`` for the + info section. + :param info_sep: the separator between multiple info items (eta etc.) + :param width: the width of the progress bar in characters, 0 means full + terminal width + :param file: the file to write to. If this is not a terminal then + only the label is printed. + :param color: controls if the terminal supports ANSI colors or not. The + default is autodetection. This is only needed if ANSI + codes are included anywhere in the progress bar output + which is not the case by default. + """ + from ._termui_impl import ProgressBar + color = resolve_color_default(color) + return ProgressBar(iterable=iterable, length=length, show_eta=show_eta, + show_percent=show_percent, show_pos=show_pos, + item_show_func=item_show_func, fill_char=fill_char, + empty_char=empty_char, bar_template=bar_template, + info_sep=info_sep, file=file, label=label, + width=width, color=color) + + +def clear(): + """Clears the terminal screen. This will have the effect of clearing + the whole visible space of the terminal and moving the cursor to the + top left. This does not do anything if not connected to a terminal. + + .. versionadded:: 2.0 + """ + if not isatty(sys.stdout): + return + # If we're on Windows and we don't have colorama available, then we + # clear the screen by shelling out. Otherwise we can use an escape + # sequence. + if WIN: + os.system('cls') + else: + sys.stdout.write('\033[2J\033[1;1H') + + +def style(text, fg=None, bg=None, bold=None, dim=None, underline=None, + blink=None, reverse=None, reset=True): + """Styles a text with ANSI styles and returns the new string. By + default the styling is self contained which means that at the end + of the string a reset code is issued. This can be prevented by + passing ``reset=False``. + + Examples:: + + click.echo(click.style('Hello World!', fg='green')) + click.echo(click.style('ATTENTION!', blink=True)) + click.echo(click.style('Some things', reverse=True, fg='cyan')) + + Supported color names: + + * ``black`` (might be a gray) + * ``red`` + * ``green`` + * ``yellow`` (might be an orange) + * ``blue`` + * ``magenta`` + * ``cyan`` + * ``white`` (might be light gray) + * ``reset`` (reset the color code only) + + .. versionadded:: 2.0 + + :param text: the string to style with ansi codes. + :param fg: if provided this will become the foreground color. + :param bg: if provided this will become the background color. + :param bold: if provided this will enable or disable bold mode. + :param dim: if provided this will enable or disable dim mode. This is + badly supported. + :param underline: if provided this will enable or disable underline. + :param blink: if provided this will enable or disable blinking. + :param reverse: if provided this will enable or disable inverse + rendering (foreground becomes background and the + other way round). + :param reset: by default a reset-all code is added at the end of the + string which means that styles do not carry over. This + can be disabled to compose styles. + """ + bits = [] + if fg: + try: + bits.append('\033[%dm' % (_ansi_colors.index(fg) + 30)) + except ValueError: + raise TypeError('Unknown color %r' % fg) + if bg: + try: + bits.append('\033[%dm' % (_ansi_colors.index(bg) + 40)) + except ValueError: + raise TypeError('Unknown color %r' % bg) + if bold is not None: + bits.append('\033[%dm' % (1 if bold else 22)) + if dim is not None: + bits.append('\033[%dm' % (2 if dim else 22)) + if underline is not None: + bits.append('\033[%dm' % (4 if underline else 24)) + if blink is not None: + bits.append('\033[%dm' % (5 if blink else 25)) + if reverse is not None: + bits.append('\033[%dm' % (7 if reverse else 27)) + bits.append(text) + if reset: + bits.append(_ansi_reset_all) + return ''.join(bits) + + +def unstyle(text): + """Removes ANSI styling information from a string. Usually it's not + necessary to use this function as Click's echo function will + automatically remove styling if necessary. + + .. versionadded:: 2.0 + + :param text: the text to remove style information from. + """ + return strip_ansi(text) + + +def secho(text, file=None, nl=True, err=False, color=None, **styles): + """This function combines :func:`echo` and :func:`style` into one + call. As such the following two calls are the same:: + + click.secho('Hello World!', fg='green') + click.echo(click.style('Hello World!', fg='green')) + + All keyword arguments are forwarded to the underlying functions + depending on which one they go with. + + .. versionadded:: 2.0 + """ + return echo(style(text, **styles), file=file, nl=nl, err=err, color=color) + + +def edit(text=None, editor=None, env=None, require_save=True, + extension='.txt', filename=None): + r"""Edits the given text in the defined editor. If an editor is given + (should be the full path to the executable but the regular operating + system search path is used for finding the executable) it overrides + the detected editor. Optionally, some environment variables can be + used. If the editor is closed without changes, `None` is returned. In + case a file is edited directly the return value is always `None` and + `require_save` and `extension` are ignored. + + If the editor cannot be opened a :exc:`UsageError` is raised. + + Note for Windows: to simplify cross-platform usage, the newlines are + automatically converted from POSIX to Windows and vice versa. As such, + the message here will have ``\n`` as newline markers. + + :param text: the text to edit. + :param editor: optionally the editor to use. Defaults to automatic + detection. + :param env: environment variables to forward to the editor. + :param require_save: if this is true, then not saving in the editor + will make the return value become `None`. + :param extension: the extension to tell the editor about. This defaults + to `.txt` but changing this might change syntax + highlighting. + :param filename: if provided it will edit this file instead of the + provided text contents. It will not use a temporary + file as an indirection in that case. + """ + from ._termui_impl import Editor + editor = Editor(editor=editor, env=env, require_save=require_save, + extension=extension) + if filename is None: + return editor.edit(text) + editor.edit_file(filename) + + +def launch(url, wait=False, locate=False): + """This function launches the given URL (or filename) in the default + viewer application for this file type. If this is an executable, it + might launch the executable in a new session. The return value is + the exit code of the launched application. Usually, ``0`` indicates + success. + + Examples:: + + click.launch('http://click.pocoo.org/') + click.launch('/my/downloaded/file', locate=True) + + .. versionadded:: 2.0 + + :param url: URL or filename of the thing to launch. + :param wait: waits for the program to stop. + :param locate: if this is set to `True` then instead of launching the + application associated with the URL it will attempt to + launch a file manager with the file located. This + might have weird effects if the URL does not point to + the filesystem. + """ + from ._termui_impl import open_url + return open_url(url, wait=wait, locate=locate) + + +# If this is provided, getchar() calls into this instead. This is used +# for unittesting purposes. +_getchar = None + + +def getchar(echo=False): + """Fetches a single character from the terminal and returns it. This + will always return a unicode character and under certain rare + circumstances this might return more than one character. The + situations which more than one character is returned is when for + whatever reason multiple characters end up in the terminal buffer or + standard input was not actually a terminal. + + Note that this will always read from the terminal, even if something + is piped into the standard input. + + .. versionadded:: 2.0 + + :param echo: if set to `True`, the character read will also show up on + the terminal. The default is to not show it. + """ + f = _getchar + if f is None: + from ._termui_impl import getchar as f + return f(echo) + + +def pause(info='Press any key to continue ...', err=False): + """This command stops execution and waits for the user to press any + key to continue. This is similar to the Windows batch "pause" + command. If the program is not run through a terminal, this command + will instead do nothing. + + .. versionadded:: 2.0 + + .. versionadded:: 4.0 + Added the `err` parameter. + + :param info: the info string to print before pausing. + :param err: if set to message goes to ``stderr`` instead of + ``stdout``, the same as with echo. + """ + if not isatty(sys.stdin) or not isatty(sys.stdout): + return + try: + if info: + echo(info, nl=False, err=err) + try: + getchar() + except (KeyboardInterrupt, EOFError): + pass + finally: + if info: + echo(err=err) diff --git a/pyextra/click/testing.py b/pyextra/click/testing.py new file mode 100644 index 00000000000000..4416c774136dc9 --- /dev/null +++ b/pyextra/click/testing.py @@ -0,0 +1,322 @@ +import os +import sys +import shutil +import tempfile +import contextlib + +from ._compat import iteritems, PY2 + + +# If someone wants to vendor click, we want to ensure the +# correct package is discovered. Ideally we could use a +# relative import here but unfortunately Python does not +# support that. +clickpkg = sys.modules[__name__.rsplit('.', 1)[0]] + + +if PY2: + from cStringIO import StringIO +else: + import io + from ._compat import _find_binary_reader + + +class EchoingStdin(object): + + def __init__(self, input, output): + self._input = input + self._output = output + + def __getattr__(self, x): + return getattr(self._input, x) + + def _echo(self, rv): + self._output.write(rv) + return rv + + def read(self, n=-1): + return self._echo(self._input.read(n)) + + def readline(self, n=-1): + return self._echo(self._input.readline(n)) + + def readlines(self): + return [self._echo(x) for x in self._input.readlines()] + + def __iter__(self): + return iter(self._echo(x) for x in self._input) + + def __repr__(self): + return repr(self._input) + + +def make_input_stream(input, charset): + # Is already an input stream. + if hasattr(input, 'read'): + if PY2: + return input + rv = _find_binary_reader(input) + if rv is not None: + return rv + raise TypeError('Could not find binary reader for input stream.') + + if input is None: + input = b'' + elif not isinstance(input, bytes): + input = input.encode(charset) + if PY2: + return StringIO(input) + return io.BytesIO(input) + + +class Result(object): + """Holds the captured result of an invoked CLI script.""" + + def __init__(self, runner, output_bytes, exit_code, exception, + exc_info=None): + #: The runner that created the result + self.runner = runner + #: The output as bytes. + self.output_bytes = output_bytes + #: The exit code as integer. + self.exit_code = exit_code + #: The exception that happend if one did. + self.exception = exception + #: The traceback + self.exc_info = exc_info + + @property + def output(self): + """The output as unicode string.""" + return self.output_bytes.decode(self.runner.charset, 'replace') \ + .replace('\r\n', '\n') + + def __repr__(self): + return '' % ( + self.exception and repr(self.exception) or 'okay', + ) + + +class CliRunner(object): + """The CLI runner provides functionality to invoke a Click command line + script for unittesting purposes in a isolated environment. This only + works in single-threaded systems without any concurrency as it changes the + global interpreter state. + + :param charset: the character set for the input and output data. This is + UTF-8 by default and should not be changed currently as + the reporting to Click only works in Python 2 properly. + :param env: a dictionary with environment variables for overriding. + :param echo_stdin: if this is set to `True`, then reading from stdin writes + to stdout. This is useful for showing examples in + some circumstances. Note that regular prompts + will automatically echo the input. + """ + + def __init__(self, charset=None, env=None, echo_stdin=False): + if charset is None: + charset = 'utf-8' + self.charset = charset + self.env = env or {} + self.echo_stdin = echo_stdin + + def get_default_prog_name(self, cli): + """Given a command object it will return the default program name + for it. The default is the `name` attribute or ``"root"`` if not + set. + """ + return cli.name or 'root' + + def make_env(self, overrides=None): + """Returns the environment overrides for invoking a script.""" + rv = dict(self.env) + if overrides: + rv.update(overrides) + return rv + + @contextlib.contextmanager + def isolation(self, input=None, env=None, color=False): + """A context manager that sets up the isolation for invoking of a + command line tool. This sets up stdin with the given input data + and `os.environ` with the overrides from the given dictionary. + This also rebinds some internals in Click to be mocked (like the + prompt functionality). + + This is automatically done in the :meth:`invoke` method. + + .. versionadded:: 4.0 + The ``color`` parameter was added. + + :param input: the input stream to put into sys.stdin. + :param env: the environment overrides as dictionary. + :param color: whether the output should contain color codes. The + application can still override this explicitly. + """ + input = make_input_stream(input, self.charset) + + old_stdin = sys.stdin + old_stdout = sys.stdout + old_stderr = sys.stderr + old_forced_width = clickpkg.formatting.FORCED_WIDTH + clickpkg.formatting.FORCED_WIDTH = 80 + + env = self.make_env(env) + + if PY2: + sys.stdout = sys.stderr = bytes_output = StringIO() + if self.echo_stdin: + input = EchoingStdin(input, bytes_output) + else: + bytes_output = io.BytesIO() + if self.echo_stdin: + input = EchoingStdin(input, bytes_output) + input = io.TextIOWrapper(input, encoding=self.charset) + sys.stdout = sys.stderr = io.TextIOWrapper( + bytes_output, encoding=self.charset) + + sys.stdin = input + + def visible_input(prompt=None): + sys.stdout.write(prompt or '') + val = input.readline().rstrip('\r\n') + sys.stdout.write(val + '\n') + sys.stdout.flush() + return val + + def hidden_input(prompt=None): + sys.stdout.write((prompt or '') + '\n') + sys.stdout.flush() + return input.readline().rstrip('\r\n') + + def _getchar(echo): + char = sys.stdin.read(1) + if echo: + sys.stdout.write(char) + sys.stdout.flush() + return char + + default_color = color + def should_strip_ansi(stream=None, color=None): + if color is None: + return not default_color + return not color + + old_visible_prompt_func = clickpkg.termui.visible_prompt_func + old_hidden_prompt_func = clickpkg.termui.hidden_prompt_func + old__getchar_func = clickpkg.termui._getchar + old_should_strip_ansi = clickpkg.utils.should_strip_ansi + clickpkg.termui.visible_prompt_func = visible_input + clickpkg.termui.hidden_prompt_func = hidden_input + clickpkg.termui._getchar = _getchar + clickpkg.utils.should_strip_ansi = should_strip_ansi + + old_env = {} + try: + for key, value in iteritems(env): + old_env[key] = os.environ.get(key) + if value is None: + try: + del os.environ[key] + except Exception: + pass + else: + os.environ[key] = value + yield bytes_output + finally: + for key, value in iteritems(old_env): + if value is None: + try: + del os.environ[key] + except Exception: + pass + else: + os.environ[key] = value + sys.stdout = old_stdout + sys.stderr = old_stderr + sys.stdin = old_stdin + clickpkg.termui.visible_prompt_func = old_visible_prompt_func + clickpkg.termui.hidden_prompt_func = old_hidden_prompt_func + clickpkg.termui._getchar = old__getchar_func + clickpkg.utils.should_strip_ansi = old_should_strip_ansi + clickpkg.formatting.FORCED_WIDTH = old_forced_width + + def invoke(self, cli, args=None, input=None, env=None, + catch_exceptions=True, color=False, **extra): + """Invokes a command in an isolated environment. The arguments are + forwarded directly to the command line script, the `extra` keyword + arguments are passed to the :meth:`~clickpkg.Command.main` function of + the command. + + This returns a :class:`Result` object. + + .. versionadded:: 3.0 + The ``catch_exceptions`` parameter was added. + + .. versionchanged:: 3.0 + The result object now has an `exc_info` attribute with the + traceback if available. + + .. versionadded:: 4.0 + The ``color`` parameter was added. + + :param cli: the command to invoke + :param args: the arguments to invoke + :param input: the input data for `sys.stdin`. + :param env: the environment overrides. + :param catch_exceptions: Whether to catch any other exceptions than + ``SystemExit``. + :param extra: the keyword arguments to pass to :meth:`main`. + :param color: whether the output should contain color codes. The + application can still override this explicitly. + """ + exc_info = None + with self.isolation(input=input, env=env, color=color) as out: + exception = None + exit_code = 0 + + try: + cli.main(args=args or (), + prog_name=self.get_default_prog_name(cli), **extra) + except SystemExit as e: + if e.code != 0: + exception = e + + exc_info = sys.exc_info() + + exit_code = e.code + if not isinstance(exit_code, int): + sys.stdout.write(str(exit_code)) + sys.stdout.write('\n') + exit_code = 1 + except Exception as e: + if not catch_exceptions: + raise + exception = e + exit_code = -1 + exc_info = sys.exc_info() + finally: + sys.stdout.flush() + output = out.getvalue() + + return Result(runner=self, + output_bytes=output, + exit_code=exit_code, + exception=exception, + exc_info=exc_info) + + @contextlib.contextmanager + def isolated_filesystem(self): + """A context manager that creates a temporary folder and changes + the current working directory to it for isolated filesystem tests. + """ + cwd = os.getcwd() + t = tempfile.mkdtemp() + os.chdir(t) + try: + yield t + finally: + os.chdir(cwd) + try: + shutil.rmtree(t) + except (OSError, IOError): + pass diff --git a/pyextra/click/types.py b/pyextra/click/types.py new file mode 100644 index 00000000000000..36390026dcd178 --- /dev/null +++ b/pyextra/click/types.py @@ -0,0 +1,550 @@ +import os +import stat + +from ._compat import open_stream, text_type, filename_to_ui, \ + get_filesystem_encoding, get_streerror, _get_argv_encoding, PY2 +from .exceptions import BadParameter +from .utils import safecall, LazyFile + + +class ParamType(object): + """Helper for converting values through types. The following is + necessary for a valid type: + + * it needs a name + * it needs to pass through None unchanged + * it needs to convert from a string + * it needs to convert its result type through unchanged + (eg: needs to be idempotent) + * it needs to be able to deal with param and context being `None`. + This can be the case when the object is used with prompt + inputs. + """ + is_composite = False + + #: the descriptive name of this type + name = None + + #: if a list of this type is expected and the value is pulled from a + #: string environment variable, this is what splits it up. `None` + #: means any whitespace. For all parameters the general rule is that + #: whitespace splits them up. The exception are paths and files which + #: are split by ``os.path.pathsep`` by default (":" on Unix and ";" on + #: Windows). + envvar_list_splitter = None + + def __call__(self, value, param=None, ctx=None): + if value is not None: + return self.convert(value, param, ctx) + + def get_metavar(self, param): + """Returns the metavar default for this param if it provides one.""" + + def get_missing_message(self, param): + """Optionally might return extra information about a missing + parameter. + + .. versionadded:: 2.0 + """ + + def convert(self, value, param, ctx): + """Converts the value. This is not invoked for values that are + `None` (the missing value). + """ + return value + + def split_envvar_value(self, rv): + """Given a value from an environment variable this splits it up + into small chunks depending on the defined envvar list splitter. + + If the splitter is set to `None`, which means that whitespace splits, + then leading and trailing whitespace is ignored. Otherwise, leading + and trailing splitters usually lead to empty items being included. + """ + return (rv or '').split(self.envvar_list_splitter) + + def fail(self, message, param=None, ctx=None): + """Helper method to fail with an invalid value message.""" + raise BadParameter(message, ctx=ctx, param=param) + + +class CompositeParamType(ParamType): + is_composite = True + + @property + def arity(self): + raise NotImplementedError() + + +class FuncParamType(ParamType): + + def __init__(self, func): + self.name = func.__name__ + self.func = func + + def convert(self, value, param, ctx): + try: + return self.func(value) + except ValueError: + try: + value = text_type(value) + except UnicodeError: + value = str(value).decode('utf-8', 'replace') + self.fail(value, param, ctx) + + +class UnprocessedParamType(ParamType): + name = 'text' + + def convert(self, value, param, ctx): + return value + + def __repr__(self): + return 'UNPROCESSED' + + +class StringParamType(ParamType): + name = 'text' + + def convert(self, value, param, ctx): + if isinstance(value, bytes): + enc = _get_argv_encoding() + try: + value = value.decode(enc) + except UnicodeError: + fs_enc = get_filesystem_encoding() + if fs_enc != enc: + try: + value = value.decode(fs_enc) + except UnicodeError: + value = value.decode('utf-8', 'replace') + return value + return value + + def __repr__(self): + return 'STRING' + + +class Choice(ParamType): + """The choice type allows a value to be checked against a fixed set of + supported values. All of these values have to be strings. + + See :ref:`choice-opts` for an example. + """ + name = 'choice' + + def __init__(self, choices): + self.choices = choices + + def get_metavar(self, param): + return '[%s]' % '|'.join(self.choices) + + def get_missing_message(self, param): + return 'Choose from %s.' % ', '.join(self.choices) + + def convert(self, value, param, ctx): + # Exact match + if value in self.choices: + return value + + # Match through normalization + if ctx is not None and \ + ctx.token_normalize_func is not None: + value = ctx.token_normalize_func(value) + for choice in self.choices: + if ctx.token_normalize_func(choice) == value: + return choice + + self.fail('invalid choice: %s. (choose from %s)' % + (value, ', '.join(self.choices)), param, ctx) + + def __repr__(self): + return 'Choice(%r)' % list(self.choices) + + +class IntParamType(ParamType): + name = 'integer' + + def convert(self, value, param, ctx): + try: + return int(value) + except (ValueError, UnicodeError): + self.fail('%s is not a valid integer' % value, param, ctx) + + def __repr__(self): + return 'INT' + + +class IntRange(IntParamType): + """A parameter that works similar to :data:`click.INT` but restricts + the value to fit into a range. The default behavior is to fail if the + value falls outside the range, but it can also be silently clamped + between the two edges. + + See :ref:`ranges` for an example. + """ + name = 'integer range' + + def __init__(self, min=None, max=None, clamp=False): + self.min = min + self.max = max + self.clamp = clamp + + def convert(self, value, param, ctx): + rv = IntParamType.convert(self, value, param, ctx) + if self.clamp: + if self.min is not None and rv < self.min: + return self.min + if self.max is not None and rv > self.max: + return self.max + if self.min is not None and rv < self.min or \ + self.max is not None and rv > self.max: + if self.min is None: + self.fail('%s is bigger than the maximum valid value ' + '%s.' % (rv, self.max), param, ctx) + elif self.max is None: + self.fail('%s is smaller than the minimum valid value ' + '%s.' % (rv, self.min), param, ctx) + else: + self.fail('%s is not in the valid range of %s to %s.' + % (rv, self.min, self.max), param, ctx) + return rv + + def __repr__(self): + return 'IntRange(%r, %r)' % (self.min, self.max) + + +class BoolParamType(ParamType): + name = 'boolean' + + def convert(self, value, param, ctx): + if isinstance(value, bool): + return bool(value) + value = value.lower() + if value in ('true', '1', 'yes', 'y'): + return True + elif value in ('false', '0', 'no', 'n'): + return False + self.fail('%s is not a valid boolean' % value, param, ctx) + + def __repr__(self): + return 'BOOL' + + +class FloatParamType(ParamType): + name = 'float' + + def convert(self, value, param, ctx): + try: + return float(value) + except (UnicodeError, ValueError): + self.fail('%s is not a valid floating point value' % + value, param, ctx) + + def __repr__(self): + return 'FLOAT' + + +class UUIDParameterType(ParamType): + name = 'uuid' + + def convert(self, value, param, ctx): + import uuid + try: + if PY2 and isinstance(value, text_type): + value = value.encode('ascii') + return uuid.UUID(value) + except (UnicodeError, ValueError): + self.fail('%s is not a valid UUID value' % value, param, ctx) + + def __repr__(self): + return 'UUID' + + +class File(ParamType): + """Declares a parameter to be a file for reading or writing. The file + is automatically closed once the context tears down (after the command + finished working). + + Files can be opened for reading or writing. The special value ``-`` + indicates stdin or stdout depending on the mode. + + By default, the file is opened for reading text data, but it can also be + opened in binary mode or for writing. The encoding parameter can be used + to force a specific encoding. + + The `lazy` flag controls if the file should be opened immediately or + upon first IO. The default is to be non lazy for standard input and + output streams as well as files opened for reading, lazy otherwise. + + Starting with Click 2.0, files can also be opened atomically in which + case all writes go into a separate file in the same folder and upon + completion the file will be moved over to the original location. This + is useful if a file regularly read by other users is modified. + + See :ref:`file-args` for more information. + """ + name = 'filename' + envvar_list_splitter = os.path.pathsep + + def __init__(self, mode='r', encoding=None, errors='strict', lazy=None, + atomic=False): + self.mode = mode + self.encoding = encoding + self.errors = errors + self.lazy = lazy + self.atomic = atomic + + def resolve_lazy_flag(self, value): + if self.lazy is not None: + return self.lazy + if value == '-': + return False + elif 'w' in self.mode: + return True + return False + + def convert(self, value, param, ctx): + try: + if hasattr(value, 'read') or hasattr(value, 'write'): + return value + + lazy = self.resolve_lazy_flag(value) + + if lazy: + f = LazyFile(value, self.mode, self.encoding, self.errors, + atomic=self.atomic) + if ctx is not None: + ctx.call_on_close(f.close_intelligently) + return f + + f, should_close = open_stream(value, self.mode, + self.encoding, self.errors, + atomic=self.atomic) + # If a context is provided, we automatically close the file + # at the end of the context execution (or flush out). If a + # context does not exist, it's the caller's responsibility to + # properly close the file. This for instance happens when the + # type is used with prompts. + if ctx is not None: + if should_close: + ctx.call_on_close(safecall(f.close)) + else: + ctx.call_on_close(safecall(f.flush)) + return f + except (IOError, OSError) as e: + self.fail('Could not open file: %s: %s' % ( + filename_to_ui(value), + get_streerror(e), + ), param, ctx) + + +class Path(ParamType): + """The path type is similar to the :class:`File` type but it performs + different checks. First of all, instead of returning an open file + handle it returns just the filename. Secondly, it can perform various + basic checks about what the file or directory should be. + + .. versionchanged:: 6.0 + `allow_dash` was added. + + :param exists: if set to true, the file or directory needs to exist for + this value to be valid. If this is not required and a + file does indeed not exist, then all further checks are + silently skipped. + :param file_okay: controls if a file is a possible value. + :param dir_okay: controls if a directory is a possible value. + :param writable: if true, a writable check is performed. + :param readable: if true, a readable check is performed. + :param resolve_path: if this is true, then the path is fully resolved + before the value is passed onwards. This means + that it's absolute and symlinks are resolved. + :param allow_dash: If this is set to `True`, a single dash to indicate + standard streams is permitted. + :param type: optionally a string type that should be used to + represent the path. The default is `None` which + means the return value will be either bytes or + unicode depending on what makes most sense given the + input data Click deals with. + """ + envvar_list_splitter = os.path.pathsep + + def __init__(self, exists=False, file_okay=True, dir_okay=True, + writable=False, readable=True, resolve_path=False, + allow_dash=False, path_type=None): + self.exists = exists + self.file_okay = file_okay + self.dir_okay = dir_okay + self.writable = writable + self.readable = readable + self.resolve_path = resolve_path + self.allow_dash = allow_dash + self.type = path_type + + if self.file_okay and not self.dir_okay: + self.name = 'file' + self.path_type = 'File' + if self.dir_okay and not self.file_okay: + self.name = 'directory' + self.path_type = 'Directory' + else: + self.name = 'path' + self.path_type = 'Path' + + def coerce_path_result(self, rv): + if self.type is not None and not isinstance(rv, self.type): + if self.type is text_type: + rv = rv.decode(get_filesystem_encoding()) + else: + rv = rv.encode(get_filesystem_encoding()) + return rv + + def convert(self, value, param, ctx): + rv = value + + is_dash = self.file_okay and self.allow_dash and rv in (b'-', '-') + + if not is_dash: + if self.resolve_path: + rv = os.path.realpath(rv) + + try: + st = os.stat(rv) + except OSError: + if not self.exists: + return self.coerce_path_result(rv) + self.fail('%s "%s" does not exist.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + + if not self.file_okay and stat.S_ISREG(st.st_mode): + self.fail('%s "%s" is a file.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + if not self.dir_okay and stat.S_ISDIR(st.st_mode): + self.fail('%s "%s" is a directory.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + if self.writable and not os.access(value, os.W_OK): + self.fail('%s "%s" is not writable.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + if self.readable and not os.access(value, os.R_OK): + self.fail('%s "%s" is not readable.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + + return self.coerce_path_result(rv) + + +class Tuple(CompositeParamType): + """The default behavior of Click is to apply a type on a value directly. + This works well in most cases, except for when `nargs` is set to a fixed + count and different types should be used for different items. In this + case the :class:`Tuple` type can be used. This type can only be used + if `nargs` is set to a fixed number. + + For more information see :ref:`tuple-type`. + + This can be selected by using a Python tuple literal as a type. + + :param types: a list of types that should be used for the tuple items. + """ + + def __init__(self, types): + self.types = [convert_type(ty) for ty in types] + + @property + def name(self): + return "<" + " ".join(ty.name for ty in self.types) + ">" + + @property + def arity(self): + return len(self.types) + + def convert(self, value, param, ctx): + if len(value) != len(self.types): + raise TypeError('It would appear that nargs is set to conflict ' + 'with the composite type arity.') + return tuple(ty(x, param, ctx) for ty, x in zip(self.types, value)) + + +def convert_type(ty, default=None): + """Converts a callable or python ty into the most appropriate param + ty. + """ + guessed_type = False + if ty is None and default is not None: + if isinstance(default, tuple): + ty = tuple(map(type, default)) + else: + ty = type(default) + guessed_type = True + + if isinstance(ty, tuple): + return Tuple(ty) + if isinstance(ty, ParamType): + return ty + if ty is text_type or ty is str or ty is None: + return STRING + if ty is int: + return INT + # Booleans are only okay if not guessed. This is done because for + # flags the default value is actually a bit of a lie in that it + # indicates which of the flags is the one we want. See get_default() + # for more information. + if ty is bool and not guessed_type: + return BOOL + if ty is float: + return FLOAT + if guessed_type: + return STRING + + # Catch a common mistake + if __debug__: + try: + if issubclass(ty, ParamType): + raise AssertionError('Attempted to use an uninstantiated ' + 'parameter type (%s).' % ty) + except TypeError: + pass + return FuncParamType(ty) + + +#: A dummy parameter type that just does nothing. From a user's +#: perspective this appears to just be the same as `STRING` but internally +#: no string conversion takes place. This is necessary to achieve the +#: same bytes/unicode behavior on Python 2/3 in situations where you want +#: to not convert argument types. This is usually useful when working +#: with file paths as they can appear in bytes and unicode. +#: +#: For path related uses the :class:`Path` type is a better choice but +#: there are situations where an unprocessed type is useful which is why +#: it is is provided. +#: +#: .. versionadded:: 4.0 +UNPROCESSED = UnprocessedParamType() + +#: A unicode string parameter type which is the implicit default. This +#: can also be selected by using ``str`` as type. +STRING = StringParamType() + +#: An integer parameter. This can also be selected by using ``int`` as +#: type. +INT = IntParamType() + +#: A floating point value parameter. This can also be selected by using +#: ``float`` as type. +FLOAT = FloatParamType() + +#: A boolean parameter. This is the default for boolean flags. This can +#: also be selected by using ``bool`` as a type. +BOOL = BoolParamType() + +#: A UUID parameter. +UUID = UUIDParameterType() diff --git a/pyextra/click/utils.py b/pyextra/click/utils.py new file mode 100644 index 00000000000000..eee626d3fd0153 --- /dev/null +++ b/pyextra/click/utils.py @@ -0,0 +1,415 @@ +import os +import sys + +from .globals import resolve_color_default + +from ._compat import text_type, open_stream, get_filesystem_encoding, \ + get_streerror, string_types, PY2, binary_streams, text_streams, \ + filename_to_ui, auto_wrap_for_ansi, strip_ansi, should_strip_ansi, \ + _default_text_stdout, _default_text_stderr, is_bytes, WIN + +if not PY2: + from ._compat import _find_binary_writer +elif WIN: + from ._winconsole import _get_windows_argv, \ + _hash_py_argv, _initial_argv_hash + + +echo_native_types = string_types + (bytes, bytearray) + + +def _posixify(name): + return '-'.join(name.split()).lower() + + +def safecall(func): + """Wraps a function so that it swallows exceptions.""" + def wrapper(*args, **kwargs): + try: + return func(*args, **kwargs) + except Exception: + pass + return wrapper + + +def make_str(value): + """Converts a value into a valid string.""" + if isinstance(value, bytes): + try: + return value.decode(get_filesystem_encoding()) + except UnicodeError: + return value.decode('utf-8', 'replace') + return text_type(value) + + +def make_default_short_help(help, max_length=45): + words = help.split() + total_length = 0 + result = [] + done = False + + for word in words: + if word[-1:] == '.': + done = True + new_length = result and 1 + len(word) or len(word) + if total_length + new_length > max_length: + result.append('...') + done = True + else: + if result: + result.append(' ') + result.append(word) + if done: + break + total_length += new_length + + return ''.join(result) + + +class LazyFile(object): + """A lazy file works like a regular file but it does not fully open + the file but it does perform some basic checks early to see if the + filename parameter does make sense. This is useful for safely opening + files for writing. + """ + + def __init__(self, filename, mode='r', encoding=None, errors='strict', + atomic=False): + self.name = filename + self.mode = mode + self.encoding = encoding + self.errors = errors + self.atomic = atomic + + if filename == '-': + self._f, self.should_close = open_stream(filename, mode, + encoding, errors) + else: + if 'r' in mode: + # Open and close the file in case we're opening it for + # reading so that we can catch at least some errors in + # some cases early. + open(filename, mode).close() + self._f = None + self.should_close = True + + def __getattr__(self, name): + return getattr(self.open(), name) + + def __repr__(self): + if self._f is not None: + return repr(self._f) + return '' % (self.name, self.mode) + + def open(self): + """Opens the file if it's not yet open. This call might fail with + a :exc:`FileError`. Not handling this error will produce an error + that Click shows. + """ + if self._f is not None: + return self._f + try: + rv, self.should_close = open_stream(self.name, self.mode, + self.encoding, + self.errors, + atomic=self.atomic) + except (IOError, OSError) as e: + from .exceptions import FileError + raise FileError(self.name, hint=get_streerror(e)) + self._f = rv + return rv + + def close(self): + """Closes the underlying file, no matter what.""" + if self._f is not None: + self._f.close() + + def close_intelligently(self): + """This function only closes the file if it was opened by the lazy + file wrapper. For instance this will never close stdin. + """ + if self.should_close: + self.close() + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close_intelligently() + + def __iter__(self): + self.open() + return iter(self._f) + + +class KeepOpenFile(object): + + def __init__(self, file): + self._file = file + + def __getattr__(self, name): + return getattr(self._file, name) + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + pass + + def __repr__(self): + return repr(self._file) + + def __iter__(self): + return iter(self._file) + + +def echo(message=None, file=None, nl=True, err=False, color=None): + """Prints a message plus a newline to the given file or stdout. On + first sight, this looks like the print function, but it has improved + support for handling Unicode and binary data that does not fail no + matter how badly configured the system is. + + Primarily it means that you can print binary data as well as Unicode + data on both 2.x and 3.x to the given file in the most appropriate way + possible. This is a very carefree function as in that it will try its + best to not fail. As of Click 6.0 this includes support for unicode + output on the Windows console. + + In addition to that, if `colorama`_ is installed, the echo function will + also support clever handling of ANSI codes. Essentially it will then + do the following: + + - add transparent handling of ANSI color codes on Windows. + - hide ANSI codes automatically if the destination file is not a + terminal. + + .. _colorama: http://pypi.python.org/pypi/colorama + + .. versionchanged:: 6.0 + As of Click 6.0 the echo function will properly support unicode + output on the windows console. Not that click does not modify + the interpreter in any way which means that `sys.stdout` or the + print statement or function will still not provide unicode support. + + .. versionchanged:: 2.0 + Starting with version 2.0 of Click, the echo function will work + with colorama if it's installed. + + .. versionadded:: 3.0 + The `err` parameter was added. + + .. versionchanged:: 4.0 + Added the `color` flag. + + :param message: the message to print + :param file: the file to write to (defaults to ``stdout``) + :param err: if set to true the file defaults to ``stderr`` instead of + ``stdout``. This is faster and easier than calling + :func:`get_text_stderr` yourself. + :param nl: if set to `True` (the default) a newline is printed afterwards. + :param color: controls if the terminal supports ANSI colors or not. The + default is autodetection. + """ + if file is None: + if err: + file = _default_text_stderr() + else: + file = _default_text_stdout() + + # Convert non bytes/text into the native string type. + if message is not None and not isinstance(message, echo_native_types): + message = text_type(message) + + if nl: + message = message or u'' + if isinstance(message, text_type): + message += u'\n' + else: + message += b'\n' + + # If there is a message, and we're in Python 3, and the value looks + # like bytes, we manually need to find the binary stream and write the + # message in there. This is done separately so that most stream + # types will work as you would expect. Eg: you can write to StringIO + # for other cases. + if message and not PY2 and is_bytes(message): + binary_file = _find_binary_writer(file) + if binary_file is not None: + file.flush() + binary_file.write(message) + binary_file.flush() + return + + # ANSI-style support. If there is no message or we are dealing with + # bytes nothing is happening. If we are connected to a file we want + # to strip colors. If we are on windows we either wrap the stream + # to strip the color or we use the colorama support to translate the + # ansi codes to API calls. + if message and not is_bytes(message): + color = resolve_color_default(color) + if should_strip_ansi(file, color): + message = strip_ansi(message) + elif WIN: + if auto_wrap_for_ansi is not None: + file = auto_wrap_for_ansi(file) + elif not color: + message = strip_ansi(message) + + if message: + file.write(message) + file.flush() + + +def get_binary_stream(name): + """Returns a system stream for byte processing. This essentially + returns the stream from the sys module with the given name but it + solves some compatibility issues between different Python versions. + Primarily this function is necessary for getting binary streams on + Python 3. + + :param name: the name of the stream to open. Valid names are ``'stdin'``, + ``'stdout'`` and ``'stderr'`` + """ + opener = binary_streams.get(name) + if opener is None: + raise TypeError('Unknown standard stream %r' % name) + return opener() + + +def get_text_stream(name, encoding=None, errors='strict'): + """Returns a system stream for text processing. This usually returns + a wrapped stream around a binary stream returned from + :func:`get_binary_stream` but it also can take shortcuts on Python 3 + for already correctly configured streams. + + :param name: the name of the stream to open. Valid names are ``'stdin'``, + ``'stdout'`` and ``'stderr'`` + :param encoding: overrides the detected default encoding. + :param errors: overrides the default error mode. + """ + opener = text_streams.get(name) + if opener is None: + raise TypeError('Unknown standard stream %r' % name) + return opener(encoding, errors) + + +def open_file(filename, mode='r', encoding=None, errors='strict', + lazy=False, atomic=False): + """This is similar to how the :class:`File` works but for manual + usage. Files are opened non lazy by default. This can open regular + files as well as stdin/stdout if ``'-'`` is passed. + + If stdin/stdout is returned the stream is wrapped so that the context + manager will not close the stream accidentally. This makes it possible + to always use the function like this without having to worry to + accidentally close a standard stream:: + + with open_file(filename) as f: + ... + + .. versionadded:: 3.0 + + :param filename: the name of the file to open (or ``'-'`` for stdin/stdout). + :param mode: the mode in which to open the file. + :param encoding: the encoding to use. + :param errors: the error handling for this file. + :param lazy: can be flipped to true to open the file lazily. + :param atomic: in atomic mode writes go into a temporary file and it's + moved on close. + """ + if lazy: + return LazyFile(filename, mode, encoding, errors, atomic=atomic) + f, should_close = open_stream(filename, mode, encoding, errors, + atomic=atomic) + if not should_close: + f = KeepOpenFile(f) + return f + + +def get_os_args(): + """This returns the argument part of sys.argv in the most appropriate + form for processing. What this means is that this return value is in + a format that works for Click to process but does not necessarily + correspond well to what's actually standard for the interpreter. + + On most environments the return value is ``sys.argv[:1]`` unchanged. + However if you are on Windows and running Python 2 the return value + will actually be a list of unicode strings instead because the + default behavior on that platform otherwise will not be able to + carry all possible values that sys.argv can have. + + .. versionadded:: 6.0 + """ + # We can only extract the unicode argv if sys.argv has not been + # changed since the startup of the application. + if PY2 and WIN and _initial_argv_hash == _hash_py_argv(): + return _get_windows_argv() + return sys.argv[1:] + + +def format_filename(filename, shorten=False): + """Formats a filename for user display. The main purpose of this + function is to ensure that the filename can be displayed at all. This + will decode the filename to unicode if necessary in a way that it will + not fail. Optionally, it can shorten the filename to not include the + full path to the filename. + + :param filename: formats a filename for UI display. This will also convert + the filename into unicode without failing. + :param shorten: this optionally shortens the filename to strip of the + path that leads up to it. + """ + if shorten: + filename = os.path.basename(filename) + return filename_to_ui(filename) + + +def get_app_dir(app_name, roaming=True, force_posix=False): + r"""Returns the config folder for the application. The default behavior + is to return whatever is most appropriate for the operating system. + + To give you an idea, for an app called ``"Foo Bar"``, something like + the following folders could be returned: + + Mac OS X: + ``~/Library/Application Support/Foo Bar`` + Mac OS X (POSIX): + ``~/.foo-bar`` + Unix: + ``~/.config/foo-bar`` + Unix (POSIX): + ``~/.foo-bar`` + Win XP (roaming): + ``C:\Documents and Settings\\Local Settings\Application Data\Foo Bar`` + Win XP (not roaming): + ``C:\Documents and Settings\\Application Data\Foo Bar`` + Win 7 (roaming): + ``C:\Users\\AppData\Roaming\Foo Bar`` + Win 7 (not roaming): + ``C:\Users\\AppData\Local\Foo Bar`` + + .. versionadded:: 2.0 + + :param app_name: the application name. This should be properly capitalized + and can contain whitespace. + :param roaming: controls if the folder should be roaming or not on Windows. + Has no affect otherwise. + :param force_posix: if this is set to `True` then on any POSIX system the + folder will be stored in the home folder with a leading + dot instead of the XDG config home or darwin's + application support folder. + """ + if WIN: + key = roaming and 'APPDATA' or 'LOCALAPPDATA' + folder = os.environ.get(key) + if folder is None: + folder = os.path.expanduser('~') + return os.path.join(folder, app_name) + if force_posix: + return os.path.join(os.path.expanduser('~/.' + _posixify(app_name))) + if sys.platform == 'darwin': + return os.path.join(os.path.expanduser( + '~/Library/Application Support'), app_name) + return os.path.join( + os.environ.get('XDG_CONFIG_HOME', os.path.expanduser('~/.config')), + _posixify(app_name)) diff --git a/pyextra/flask/__init__.py b/pyextra/flask/__init__.py new file mode 100644 index 00000000000000..ded19822400ad7 --- /dev/null +++ b/pyextra/flask/__init__.py @@ -0,0 +1,49 @@ +# -*- coding: utf-8 -*- +""" + flask + ~~~~~ + + A microframework based on Werkzeug. It's extensively documented + and follows best practice patterns. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +__version__ = '1.0.2' + +# utilities we import from Werkzeug and Jinja2 that are unused +# in the module but are exported as public interface. +from werkzeug.exceptions import abort +from werkzeug.utils import redirect +from jinja2 import Markup, escape + +from .app import Flask, Request, Response +from .config import Config +from .helpers import url_for, flash, send_file, send_from_directory, \ + get_flashed_messages, get_template_attribute, make_response, safe_join, \ + stream_with_context +from .globals import current_app, g, request, session, _request_ctx_stack, \ + _app_ctx_stack +from .ctx import has_request_context, has_app_context, \ + after_this_request, copy_current_request_context +from .blueprints import Blueprint +from .templating import render_template, render_template_string + +# the signals +from .signals import signals_available, template_rendered, request_started, \ + request_finished, got_request_exception, request_tearing_down, \ + appcontext_tearing_down, appcontext_pushed, \ + appcontext_popped, message_flashed, before_render_template + +# We're not exposing the actual json module but a convenient wrapper around +# it. +from . import json + +# This was the only thing that Flask used to export at one point and it had +# a more generic name. +jsonify = json.jsonify + +# backwards compat, goes away in 1.0 +from .sessions import SecureCookieSession as Session +json_available = True diff --git a/pyextra/flask/__main__.py b/pyextra/flask/__main__.py new file mode 100644 index 00000000000000..4aee654374633d --- /dev/null +++ b/pyextra/flask/__main__.py @@ -0,0 +1,14 @@ +# -*- coding: utf-8 -*- +""" + flask.__main__ + ~~~~~~~~~~~~~~ + + Alias for flask.run for the command line. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +if __name__ == '__main__': + from .cli import main + main(as_module=True) diff --git a/pyextra/flask/_compat.py b/pyextra/flask/_compat.py new file mode 100644 index 00000000000000..a3b5b9c1c9ade6 --- /dev/null +++ b/pyextra/flask/_compat.py @@ -0,0 +1,99 @@ +# -*- coding: utf-8 -*- +""" + flask._compat + ~~~~~~~~~~~~~ + + Some py2/py3 compatibility support based on a stripped down + version of six so we don't have to depend on a specific version + of it. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import sys + +PY2 = sys.version_info[0] == 2 +_identity = lambda x: x + + +if not PY2: + text_type = str + string_types = (str,) + integer_types = (int,) + + iterkeys = lambda d: iter(d.keys()) + itervalues = lambda d: iter(d.values()) + iteritems = lambda d: iter(d.items()) + + from inspect import getfullargspec as getargspec + from io import StringIO + + def reraise(tp, value, tb=None): + if value.__traceback__ is not tb: + raise value.with_traceback(tb) + raise value + + implements_to_string = _identity + +else: + text_type = unicode + string_types = (str, unicode) + integer_types = (int, long) + + iterkeys = lambda d: d.iterkeys() + itervalues = lambda d: d.itervalues() + iteritems = lambda d: d.iteritems() + + from inspect import getargspec + from cStringIO import StringIO + + exec('def reraise(tp, value, tb=None):\n raise tp, value, tb') + + def implements_to_string(cls): + cls.__unicode__ = cls.__str__ + cls.__str__ = lambda x: x.__unicode__().encode('utf-8') + return cls + + +def with_metaclass(meta, *bases): + """Create a base class with a metaclass.""" + # This requires a bit of explanation: the basic idea is to make a + # dummy metaclass for one level of class instantiation that replaces + # itself with the actual metaclass. + class metaclass(type): + def __new__(cls, name, this_bases, d): + return meta(name, bases, d) + return type.__new__(metaclass, 'temporary_class', (), {}) + + +# Certain versions of pypy have a bug where clearing the exception stack +# breaks the __exit__ function in a very peculiar way. The second level of +# exception blocks is necessary because pypy seems to forget to check if an +# exception happened until the next bytecode instruction? +# +# Relevant PyPy bugfix commit: +# https://bitbucket.org/pypy/pypy/commits/77ecf91c635a287e88e60d8ddb0f4e9df4003301 +# According to ronan on #pypy IRC, it is released in PyPy2 2.3 and later +# versions. +# +# Ubuntu 14.04 has PyPy 2.2.1, which does exhibit this bug. +BROKEN_PYPY_CTXMGR_EXIT = False +if hasattr(sys, 'pypy_version_info'): + class _Mgr(object): + def __enter__(self): + return self + def __exit__(self, *args): + if hasattr(sys, 'exc_clear'): + # Python 3 (PyPy3) doesn't have exc_clear + sys.exc_clear() + try: + try: + with _Mgr(): + raise AssertionError() + except: + raise + except TypeError: + BROKEN_PYPY_CTXMGR_EXIT = True + except AssertionError: + pass diff --git a/pyextra/flask/app.py b/pyextra/flask/app.py new file mode 100644 index 00000000000000..87c5900348b5a2 --- /dev/null +++ b/pyextra/flask/app.py @@ -0,0 +1,2315 @@ +# -*- coding: utf-8 -*- +""" + flask.app + ~~~~~~~~~ + + This module implements the central WSGI application object. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +import sys +import warnings +from datetime import timedelta +from functools import update_wrapper +from itertools import chain +from threading import Lock + +from werkzeug.datastructures import Headers, ImmutableDict +from werkzeug.exceptions import BadRequest, BadRequestKeyError, HTTPException, \ + InternalServerError, MethodNotAllowed, default_exceptions +from werkzeug.routing import BuildError, Map, RequestRedirect, Rule + +from . import cli, json +from ._compat import integer_types, reraise, string_types, text_type +from .config import Config, ConfigAttribute +from .ctx import AppContext, RequestContext, _AppCtxGlobals +from .globals import _request_ctx_stack, g, request, session +from .helpers import ( + _PackageBoundObject, + _endpoint_from_view_func, find_package, get_env, get_debug_flag, + get_flashed_messages, locked_cached_property, url_for, get_load_dotenv +) +from .logging import create_logger +from .sessions import SecureCookieSessionInterface +from .signals import appcontext_tearing_down, got_request_exception, \ + request_finished, request_started, request_tearing_down +from .templating import DispatchingJinjaLoader, Environment, \ + _default_template_ctx_processor +from .wrappers import Request, Response + +# a singleton sentinel value for parameter defaults +_sentinel = object() + + +def _make_timedelta(value): + if not isinstance(value, timedelta): + return timedelta(seconds=value) + return value + + +def setupmethod(f): + """Wraps a method so that it performs a check in debug mode if the + first request was already handled. + """ + def wrapper_func(self, *args, **kwargs): + if self.debug and self._got_first_request: + raise AssertionError('A setup function was called after the ' + 'first request was handled. This usually indicates a bug ' + 'in the application where a module was not imported ' + 'and decorators or other functionality was called too late.\n' + 'To fix this make sure to import all your view modules, ' + 'database models and everything related at a central place ' + 'before the application starts serving requests.') + return f(self, *args, **kwargs) + return update_wrapper(wrapper_func, f) + + +class Flask(_PackageBoundObject): + """The flask object implements a WSGI application and acts as the central + object. It is passed the name of the module or package of the + application. Once it is created it will act as a central registry for + the view functions, the URL rules, template configuration and much more. + + The name of the package is used to resolve resources from inside the + package or the folder the module is contained in depending on if the + package parameter resolves to an actual python package (a folder with + an :file:`__init__.py` file inside) or a standard module (just a ``.py`` file). + + For more information about resource loading, see :func:`open_resource`. + + Usually you create a :class:`Flask` instance in your main module or + in the :file:`__init__.py` file of your package like this:: + + from flask import Flask + app = Flask(__name__) + + .. admonition:: About the First Parameter + + The idea of the first parameter is to give Flask an idea of what + belongs to your application. This name is used to find resources + on the filesystem, can be used by extensions to improve debugging + information and a lot more. + + So it's important what you provide there. If you are using a single + module, `__name__` is always the correct value. If you however are + using a package, it's usually recommended to hardcode the name of + your package there. + + For example if your application is defined in :file:`yourapplication/app.py` + you should create it with one of the two versions below:: + + app = Flask('yourapplication') + app = Flask(__name__.split('.')[0]) + + Why is that? The application will work even with `__name__`, thanks + to how resources are looked up. However it will make debugging more + painful. Certain extensions can make assumptions based on the + import name of your application. For example the Flask-SQLAlchemy + extension will look for the code in your application that triggered + an SQL query in debug mode. If the import name is not properly set + up, that debugging information is lost. (For example it would only + pick up SQL queries in `yourapplication.app` and not + `yourapplication.views.frontend`) + + .. versionadded:: 0.7 + The `static_url_path`, `static_folder`, and `template_folder` + parameters were added. + + .. versionadded:: 0.8 + The `instance_path` and `instance_relative_config` parameters were + added. + + .. versionadded:: 0.11 + The `root_path` parameter was added. + + .. versionadded:: 1.0 + The ``host_matching`` and ``static_host`` parameters were added. + + .. versionadded:: 1.0 + The ``subdomain_matching`` parameter was added. Subdomain + matching needs to be enabled manually now. Setting + :data:`SERVER_NAME` does not implicitly enable it. + + :param import_name: the name of the application package + :param static_url_path: can be used to specify a different path for the + static files on the web. Defaults to the name + of the `static_folder` folder. + :param static_folder: the folder with static files that should be served + at `static_url_path`. Defaults to the ``'static'`` + folder in the root path of the application. + :param static_host: the host to use when adding the static route. + Defaults to None. Required when using ``host_matching=True`` + with a ``static_folder`` configured. + :param host_matching: set ``url_map.host_matching`` attribute. + Defaults to False. + :param subdomain_matching: consider the subdomain relative to + :data:`SERVER_NAME` when matching routes. Defaults to False. + :param template_folder: the folder that contains the templates that should + be used by the application. Defaults to + ``'templates'`` folder in the root path of the + application. + :param instance_path: An alternative instance path for the application. + By default the folder ``'instance'`` next to the + package or module is assumed to be the instance + path. + :param instance_relative_config: if set to ``True`` relative filenames + for loading the config are assumed to + be relative to the instance path instead + of the application root. + :param root_path: Flask by default will automatically calculate the path + to the root of the application. In certain situations + this cannot be achieved (for instance if the package + is a Python 3 namespace package) and needs to be + manually defined. + """ + + #: The class that is used for request objects. See :class:`~flask.Request` + #: for more information. + request_class = Request + + #: The class that is used for response objects. See + #: :class:`~flask.Response` for more information. + response_class = Response + + #: The class that is used for the Jinja environment. + #: + #: .. versionadded:: 0.11 + jinja_environment = Environment + + #: The class that is used for the :data:`~flask.g` instance. + #: + #: Example use cases for a custom class: + #: + #: 1. Store arbitrary attributes on flask.g. + #: 2. Add a property for lazy per-request database connectors. + #: 3. Return None instead of AttributeError on unexpected attributes. + #: 4. Raise exception if an unexpected attr is set, a "controlled" flask.g. + #: + #: In Flask 0.9 this property was called `request_globals_class` but it + #: was changed in 0.10 to :attr:`app_ctx_globals_class` because the + #: flask.g object is now application context scoped. + #: + #: .. versionadded:: 0.10 + app_ctx_globals_class = _AppCtxGlobals + + #: The class that is used for the ``config`` attribute of this app. + #: Defaults to :class:`~flask.Config`. + #: + #: Example use cases for a custom class: + #: + #: 1. Default values for certain config options. + #: 2. Access to config values through attributes in addition to keys. + #: + #: .. versionadded:: 0.11 + config_class = Config + + #: The testing flag. Set this to ``True`` to enable the test mode of + #: Flask extensions (and in the future probably also Flask itself). + #: For example this might activate test helpers that have an + #: additional runtime cost which should not be enabled by default. + #: + #: If this is enabled and PROPAGATE_EXCEPTIONS is not changed from the + #: default it's implicitly enabled. + #: + #: This attribute can also be configured from the config with the + #: ``TESTING`` configuration key. Defaults to ``False``. + testing = ConfigAttribute('TESTING') + + #: If a secret key is set, cryptographic components can use this to + #: sign cookies and other things. Set this to a complex random value + #: when you want to use the secure cookie for instance. + #: + #: This attribute can also be configured from the config with the + #: :data:`SECRET_KEY` configuration key. Defaults to ``None``. + secret_key = ConfigAttribute('SECRET_KEY') + + #: The secure cookie uses this for the name of the session cookie. + #: + #: This attribute can also be configured from the config with the + #: ``SESSION_COOKIE_NAME`` configuration key. Defaults to ``'session'`` + session_cookie_name = ConfigAttribute('SESSION_COOKIE_NAME') + + #: A :class:`~datetime.timedelta` which is used to set the expiration + #: date of a permanent session. The default is 31 days which makes a + #: permanent session survive for roughly one month. + #: + #: This attribute can also be configured from the config with the + #: ``PERMANENT_SESSION_LIFETIME`` configuration key. Defaults to + #: ``timedelta(days=31)`` + permanent_session_lifetime = ConfigAttribute('PERMANENT_SESSION_LIFETIME', + get_converter=_make_timedelta) + + #: A :class:`~datetime.timedelta` which is used as default cache_timeout + #: for the :func:`send_file` functions. The default is 12 hours. + #: + #: This attribute can also be configured from the config with the + #: ``SEND_FILE_MAX_AGE_DEFAULT`` configuration key. This configuration + #: variable can also be set with an integer value used as seconds. + #: Defaults to ``timedelta(hours=12)`` + send_file_max_age_default = ConfigAttribute('SEND_FILE_MAX_AGE_DEFAULT', + get_converter=_make_timedelta) + + #: Enable this if you want to use the X-Sendfile feature. Keep in + #: mind that the server has to support this. This only affects files + #: sent with the :func:`send_file` method. + #: + #: .. versionadded:: 0.2 + #: + #: This attribute can also be configured from the config with the + #: ``USE_X_SENDFILE`` configuration key. Defaults to ``False``. + use_x_sendfile = ConfigAttribute('USE_X_SENDFILE') + + #: The JSON encoder class to use. Defaults to :class:`~flask.json.JSONEncoder`. + #: + #: .. versionadded:: 0.10 + json_encoder = json.JSONEncoder + + #: The JSON decoder class to use. Defaults to :class:`~flask.json.JSONDecoder`. + #: + #: .. versionadded:: 0.10 + json_decoder = json.JSONDecoder + + #: Options that are passed directly to the Jinja2 environment. + jinja_options = ImmutableDict( + extensions=['jinja2.ext.autoescape', 'jinja2.ext.with_'] + ) + + #: Default configuration parameters. + default_config = ImmutableDict({ + 'ENV': None, + 'DEBUG': None, + 'TESTING': False, + 'PROPAGATE_EXCEPTIONS': None, + 'PRESERVE_CONTEXT_ON_EXCEPTION': None, + 'SECRET_KEY': None, + 'PERMANENT_SESSION_LIFETIME': timedelta(days=31), + 'USE_X_SENDFILE': False, + 'SERVER_NAME': None, + 'APPLICATION_ROOT': '/', + 'SESSION_COOKIE_NAME': 'session', + 'SESSION_COOKIE_DOMAIN': None, + 'SESSION_COOKIE_PATH': None, + 'SESSION_COOKIE_HTTPONLY': True, + 'SESSION_COOKIE_SECURE': False, + 'SESSION_COOKIE_SAMESITE': None, + 'SESSION_REFRESH_EACH_REQUEST': True, + 'MAX_CONTENT_LENGTH': None, + 'SEND_FILE_MAX_AGE_DEFAULT': timedelta(hours=12), + 'TRAP_BAD_REQUEST_ERRORS': None, + 'TRAP_HTTP_EXCEPTIONS': False, + 'EXPLAIN_TEMPLATE_LOADING': False, + 'PREFERRED_URL_SCHEME': 'http', + 'JSON_AS_ASCII': True, + 'JSON_SORT_KEYS': True, + 'JSONIFY_PRETTYPRINT_REGULAR': False, + 'JSONIFY_MIMETYPE': 'application/json', + 'TEMPLATES_AUTO_RELOAD': None, + 'MAX_COOKIE_SIZE': 4093, + }) + + #: The rule object to use for URL rules created. This is used by + #: :meth:`add_url_rule`. Defaults to :class:`werkzeug.routing.Rule`. + #: + #: .. versionadded:: 0.7 + url_rule_class = Rule + + #: the test client that is used with when `test_client` is used. + #: + #: .. versionadded:: 0.7 + test_client_class = None + + #: The :class:`~click.testing.CliRunner` subclass, by default + #: :class:`~flask.testing.FlaskCliRunner` that is used by + #: :meth:`test_cli_runner`. Its ``__init__`` method should take a + #: Flask app object as the first argument. + #: + #: .. versionadded:: 1.0 + test_cli_runner_class = None + + #: the session interface to use. By default an instance of + #: :class:`~flask.sessions.SecureCookieSessionInterface` is used here. + #: + #: .. versionadded:: 0.8 + session_interface = SecureCookieSessionInterface() + + # TODO remove the next three attrs when Sphinx :inherited-members: works + # https://github.com/sphinx-doc/sphinx/issues/741 + + #: The name of the package or module that this app belongs to. Do not + #: change this once it is set by the constructor. + import_name = None + + #: Location of the template files to be added to the template lookup. + #: ``None`` if templates should not be added. + template_folder = None + + #: Absolute path to the package on the filesystem. Used to look up + #: resources contained in the package. + root_path = None + + def __init__( + self, + import_name, + static_url_path=None, + static_folder='static', + static_host=None, + host_matching=False, + subdomain_matching=False, + template_folder='templates', + instance_path=None, + instance_relative_config=False, + root_path=None + ): + _PackageBoundObject.__init__( + self, + import_name, + template_folder=template_folder, + root_path=root_path + ) + + if static_url_path is not None: + self.static_url_path = static_url_path + + if static_folder is not None: + self.static_folder = static_folder + + if instance_path is None: + instance_path = self.auto_find_instance_path() + elif not os.path.isabs(instance_path): + raise ValueError( + 'If an instance path is provided it must be absolute.' + ' A relative path was given instead.' + ) + + #: Holds the path to the instance folder. + #: + #: .. versionadded:: 0.8 + self.instance_path = instance_path + + #: The configuration dictionary as :class:`Config`. This behaves + #: exactly like a regular dictionary but supports additional methods + #: to load a config from files. + self.config = self.make_config(instance_relative_config) + + #: A dictionary of all view functions registered. The keys will + #: be function names which are also used to generate URLs and + #: the values are the function objects themselves. + #: To register a view function, use the :meth:`route` decorator. + self.view_functions = {} + + #: A dictionary of all registered error handlers. The key is ``None`` + #: for error handlers active on the application, otherwise the key is + #: the name of the blueprint. Each key points to another dictionary + #: where the key is the status code of the http exception. The + #: special key ``None`` points to a list of tuples where the first item + #: is the class for the instance check and the second the error handler + #: function. + #: + #: To register an error handler, use the :meth:`errorhandler` + #: decorator. + self.error_handler_spec = {} + + #: A list of functions that are called when :meth:`url_for` raises a + #: :exc:`~werkzeug.routing.BuildError`. Each function registered here + #: is called with `error`, `endpoint` and `values`. If a function + #: returns ``None`` or raises a :exc:`BuildError` the next function is + #: tried. + #: + #: .. versionadded:: 0.9 + self.url_build_error_handlers = [] + + #: A dictionary with lists of functions that will be called at the + #: beginning of each request. The key of the dictionary is the name of + #: the blueprint this function is active for, or ``None`` for all + #: requests. To register a function, use the :meth:`before_request` + #: decorator. + self.before_request_funcs = {} + + #: A list of functions that will be called at the beginning of the + #: first request to this instance. To register a function, use the + #: :meth:`before_first_request` decorator. + #: + #: .. versionadded:: 0.8 + self.before_first_request_funcs = [] + + #: A dictionary with lists of functions that should be called after + #: each request. The key of the dictionary is the name of the blueprint + #: this function is active for, ``None`` for all requests. This can for + #: example be used to close database connections. To register a function + #: here, use the :meth:`after_request` decorator. + self.after_request_funcs = {} + + #: A dictionary with lists of functions that are called after + #: each request, even if an exception has occurred. The key of the + #: dictionary is the name of the blueprint this function is active for, + #: ``None`` for all requests. These functions are not allowed to modify + #: the request, and their return values are ignored. If an exception + #: occurred while processing the request, it gets passed to each + #: teardown_request function. To register a function here, use the + #: :meth:`teardown_request` decorator. + #: + #: .. versionadded:: 0.7 + self.teardown_request_funcs = {} + + #: A list of functions that are called when the application context + #: is destroyed. Since the application context is also torn down + #: if the request ends this is the place to store code that disconnects + #: from databases. + #: + #: .. versionadded:: 0.9 + self.teardown_appcontext_funcs = [] + + #: A dictionary with lists of functions that are called before the + #: :attr:`before_request_funcs` functions. The key of the dictionary is + #: the name of the blueprint this function is active for, or ``None`` + #: for all requests. To register a function, use + #: :meth:`url_value_preprocessor`. + #: + #: .. versionadded:: 0.7 + self.url_value_preprocessors = {} + + #: A dictionary with lists of functions that can be used as URL value + #: preprocessors. The key ``None`` here is used for application wide + #: callbacks, otherwise the key is the name of the blueprint. + #: Each of these functions has the chance to modify the dictionary + #: of URL values before they are used as the keyword arguments of the + #: view function. For each function registered this one should also + #: provide a :meth:`url_defaults` function that adds the parameters + #: automatically again that were removed that way. + #: + #: .. versionadded:: 0.7 + self.url_default_functions = {} + + #: A dictionary with list of functions that are called without argument + #: to populate the template context. The key of the dictionary is the + #: name of the blueprint this function is active for, ``None`` for all + #: requests. Each returns a dictionary that the template context is + #: updated with. To register a function here, use the + #: :meth:`context_processor` decorator. + self.template_context_processors = { + None: [_default_template_ctx_processor] + } + + #: A list of shell context processor functions that should be run + #: when a shell context is created. + #: + #: .. versionadded:: 0.11 + self.shell_context_processors = [] + + #: all the attached blueprints in a dictionary by name. Blueprints + #: can be attached multiple times so this dictionary does not tell + #: you how often they got attached. + #: + #: .. versionadded:: 0.7 + self.blueprints = {} + self._blueprint_order = [] + + #: a place where extensions can store application specific state. For + #: example this is where an extension could store database engines and + #: similar things. For backwards compatibility extensions should register + #: themselves like this:: + #: + #: if not hasattr(app, 'extensions'): + #: app.extensions = {} + #: app.extensions['extensionname'] = SomeObject() + #: + #: The key must match the name of the extension module. For example in + #: case of a "Flask-Foo" extension in `flask_foo`, the key would be + #: ``'foo'``. + #: + #: .. versionadded:: 0.7 + self.extensions = {} + + #: The :class:`~werkzeug.routing.Map` for this instance. You can use + #: this to change the routing converters after the class was created + #: but before any routes are connected. Example:: + #: + #: from werkzeug.routing import BaseConverter + #: + #: class ListConverter(BaseConverter): + #: def to_python(self, value): + #: return value.split(',') + #: def to_url(self, values): + #: return ','.join(super(ListConverter, self).to_url(value) + #: for value in values) + #: + #: app = Flask(__name__) + #: app.url_map.converters['list'] = ListConverter + self.url_map = Map() + + self.url_map.host_matching = host_matching + self.subdomain_matching = subdomain_matching + + # tracks internally if the application already handled at least one + # request. + self._got_first_request = False + self._before_request_lock = Lock() + + # Add a static route using the provided static_url_path, static_host, + # and static_folder if there is a configured static_folder. + # Note we do this without checking if static_folder exists. + # For one, it might be created while the server is running (e.g. during + # development). Also, Google App Engine stores static files somewhere + if self.has_static_folder: + assert bool(static_host) == host_matching, 'Invalid static_host/host_matching combination' + self.add_url_rule( + self.static_url_path + '/', + endpoint='static', + host=static_host, + view_func=self.send_static_file + ) + + #: The click command line context for this application. Commands + #: registered here show up in the :command:`flask` command once the + #: application has been discovered. The default commands are + #: provided by Flask itself and can be overridden. + #: + #: This is an instance of a :class:`click.Group` object. + self.cli = cli.AppGroup(self.name) + + @locked_cached_property + def name(self): + """The name of the application. This is usually the import name + with the difference that it's guessed from the run file if the + import name is main. This name is used as a display name when + Flask needs the name of the application. It can be set and overridden + to change the value. + + .. versionadded:: 0.8 + """ + if self.import_name == '__main__': + fn = getattr(sys.modules['__main__'], '__file__', None) + if fn is None: + return '__main__' + return os.path.splitext(os.path.basename(fn))[0] + return self.import_name + + @property + def propagate_exceptions(self): + """Returns the value of the ``PROPAGATE_EXCEPTIONS`` configuration + value in case it's set, otherwise a sensible default is returned. + + .. versionadded:: 0.7 + """ + rv = self.config['PROPAGATE_EXCEPTIONS'] + if rv is not None: + return rv + return self.testing or self.debug + + @property + def preserve_context_on_exception(self): + """Returns the value of the ``PRESERVE_CONTEXT_ON_EXCEPTION`` + configuration value in case it's set, otherwise a sensible default + is returned. + + .. versionadded:: 0.7 + """ + rv = self.config['PRESERVE_CONTEXT_ON_EXCEPTION'] + if rv is not None: + return rv + return self.debug + + @locked_cached_property + def logger(self): + """The ``'flask.app'`` logger, a standard Python + :class:`~logging.Logger`. + + In debug mode, the logger's :attr:`~logging.Logger.level` will be set + to :data:`~logging.DEBUG`. + + If there are no handlers configured, a default handler will be added. + See :ref:`logging` for more information. + + .. versionchanged:: 1.0 + Behavior was simplified. The logger is always named + ``flask.app``. The level is only set during configuration, it + doesn't check ``app.debug`` each time. Only one format is used, + not different ones depending on ``app.debug``. No handlers are + removed, and a handler is only added if no handlers are already + configured. + + .. versionadded:: 0.3 + """ + return create_logger(self) + + @locked_cached_property + def jinja_env(self): + """The Jinja2 environment used to load templates.""" + return self.create_jinja_environment() + + @property + def got_first_request(self): + """This attribute is set to ``True`` if the application started + handling the first request. + + .. versionadded:: 0.8 + """ + return self._got_first_request + + def make_config(self, instance_relative=False): + """Used to create the config attribute by the Flask constructor. + The `instance_relative` parameter is passed in from the constructor + of Flask (there named `instance_relative_config`) and indicates if + the config should be relative to the instance path or the root path + of the application. + + .. versionadded:: 0.8 + """ + root_path = self.root_path + if instance_relative: + root_path = self.instance_path + defaults = dict(self.default_config) + defaults['ENV'] = get_env() + defaults['DEBUG'] = get_debug_flag() + return self.config_class(root_path, defaults) + + def auto_find_instance_path(self): + """Tries to locate the instance path if it was not provided to the + constructor of the application class. It will basically calculate + the path to a folder named ``instance`` next to your main file or + the package. + + .. versionadded:: 0.8 + """ + prefix, package_path = find_package(self.import_name) + if prefix is None: + return os.path.join(package_path, 'instance') + return os.path.join(prefix, 'var', self.name + '-instance') + + def open_instance_resource(self, resource, mode='rb'): + """Opens a resource from the application's instance folder + (:attr:`instance_path`). Otherwise works like + :meth:`open_resource`. Instance resources can also be opened for + writing. + + :param resource: the name of the resource. To access resources within + subfolders use forward slashes as separator. + :param mode: resource file opening mode, default is 'rb'. + """ + return open(os.path.join(self.instance_path, resource), mode) + + def _get_templates_auto_reload(self): + """Reload templates when they are changed. Used by + :meth:`create_jinja_environment`. + + This attribute can be configured with :data:`TEMPLATES_AUTO_RELOAD`. If + not set, it will be enabled in debug mode. + + .. versionadded:: 1.0 + This property was added but the underlying config and behavior + already existed. + """ + rv = self.config['TEMPLATES_AUTO_RELOAD'] + return rv if rv is not None else self.debug + + def _set_templates_auto_reload(self, value): + self.config['TEMPLATES_AUTO_RELOAD'] = value + + templates_auto_reload = property( + _get_templates_auto_reload, _set_templates_auto_reload + ) + del _get_templates_auto_reload, _set_templates_auto_reload + + def create_jinja_environment(self): + """Creates the Jinja2 environment based on :attr:`jinja_options` + and :meth:`select_jinja_autoescape`. Since 0.7 this also adds + the Jinja2 globals and filters after initialization. Override + this function to customize the behavior. + + .. versionadded:: 0.5 + .. versionchanged:: 0.11 + ``Environment.auto_reload`` set in accordance with + ``TEMPLATES_AUTO_RELOAD`` configuration option. + """ + options = dict(self.jinja_options) + + if 'autoescape' not in options: + options['autoescape'] = self.select_jinja_autoescape + + if 'auto_reload' not in options: + options['auto_reload'] = self.templates_auto_reload + + rv = self.jinja_environment(self, **options) + rv.globals.update( + url_for=url_for, + get_flashed_messages=get_flashed_messages, + config=self.config, + # request, session and g are normally added with the + # context processor for efficiency reasons but for imported + # templates we also want the proxies in there. + request=request, + session=session, + g=g + ) + rv.filters['tojson'] = json.tojson_filter + return rv + + def create_global_jinja_loader(self): + """Creates the loader for the Jinja2 environment. Can be used to + override just the loader and keeping the rest unchanged. It's + discouraged to override this function. Instead one should override + the :meth:`jinja_loader` function instead. + + The global loader dispatches between the loaders of the application + and the individual blueprints. + + .. versionadded:: 0.7 + """ + return DispatchingJinjaLoader(self) + + def select_jinja_autoescape(self, filename): + """Returns ``True`` if autoescaping should be active for the given + template name. If no template name is given, returns `True`. + + .. versionadded:: 0.5 + """ + if filename is None: + return True + return filename.endswith(('.html', '.htm', '.xml', '.xhtml')) + + def update_template_context(self, context): + """Update the template context with some commonly used variables. + This injects request, session, config and g into the template + context as well as everything template context processors want + to inject. Note that the as of Flask 0.6, the original values + in the context will not be overridden if a context processor + decides to return a value with the same key. + + :param context: the context as a dictionary that is updated in place + to add extra variables. + """ + funcs = self.template_context_processors[None] + reqctx = _request_ctx_stack.top + if reqctx is not None: + bp = reqctx.request.blueprint + if bp is not None and bp in self.template_context_processors: + funcs = chain(funcs, self.template_context_processors[bp]) + orig_ctx = context.copy() + for func in funcs: + context.update(func()) + # make sure the original values win. This makes it possible to + # easier add new variables in context processors without breaking + # existing views. + context.update(orig_ctx) + + def make_shell_context(self): + """Returns the shell context for an interactive shell for this + application. This runs all the registered shell context + processors. + + .. versionadded:: 0.11 + """ + rv = {'app': self, 'g': g} + for processor in self.shell_context_processors: + rv.update(processor()) + return rv + + #: What environment the app is running in. Flask and extensions may + #: enable behaviors based on the environment, such as enabling debug + #: mode. This maps to the :data:`ENV` config key. This is set by the + #: :envvar:`FLASK_ENV` environment variable and may not behave as + #: expected if set in code. + #: + #: **Do not enable development when deploying in production.** + #: + #: Default: ``'production'`` + env = ConfigAttribute('ENV') + + def _get_debug(self): + return self.config['DEBUG'] + + def _set_debug(self, value): + self.config['DEBUG'] = value + self.jinja_env.auto_reload = self.templates_auto_reload + + #: Whether debug mode is enabled. When using ``flask run`` to start + #: the development server, an interactive debugger will be shown for + #: unhandled exceptions, and the server will be reloaded when code + #: changes. This maps to the :data:`DEBUG` config key. This is + #: enabled when :attr:`env` is ``'development'`` and is overridden + #: by the ``FLASK_DEBUG`` environment variable. It may not behave as + #: expected if set in code. + #: + #: **Do not enable debug mode when deploying in production.** + #: + #: Default: ``True`` if :attr:`env` is ``'development'``, or + #: ``False`` otherwise. + debug = property(_get_debug, _set_debug) + del _get_debug, _set_debug + + def run(self, host=None, port=None, debug=None, + load_dotenv=True, **options): + """Runs the application on a local development server. + + Do not use ``run()`` in a production setting. It is not intended to + meet security and performance requirements for a production server. + Instead, see :ref:`deployment` for WSGI server recommendations. + + If the :attr:`debug` flag is set the server will automatically reload + for code changes and show a debugger in case an exception happened. + + If you want to run the application in debug mode, but disable the + code execution on the interactive debugger, you can pass + ``use_evalex=False`` as parameter. This will keep the debugger's + traceback screen active, but disable code execution. + + It is not recommended to use this function for development with + automatic reloading as this is badly supported. Instead you should + be using the :command:`flask` command line script's ``run`` support. + + .. admonition:: Keep in Mind + + Flask will suppress any server error with a generic error page + unless it is in debug mode. As such to enable just the + interactive debugger without the code reloading, you have to + invoke :meth:`run` with ``debug=True`` and ``use_reloader=False``. + Setting ``use_debugger`` to ``True`` without being in debug mode + won't catch any exceptions because there won't be any to + catch. + + :param host: the hostname to listen on. Set this to ``'0.0.0.0'`` to + have the server available externally as well. Defaults to + ``'127.0.0.1'`` or the host in the ``SERVER_NAME`` config variable + if present. + :param port: the port of the webserver. Defaults to ``5000`` or the + port defined in the ``SERVER_NAME`` config variable if present. + :param debug: if given, enable or disable debug mode. See + :attr:`debug`. + :param load_dotenv: Load the nearest :file:`.env` and :file:`.flaskenv` + files to set environment variables. Will also change the working + directory to the directory containing the first file found. + :param options: the options to be forwarded to the underlying Werkzeug + server. See :func:`werkzeug.serving.run_simple` for more + information. + + .. versionchanged:: 1.0 + If installed, python-dotenv will be used to load environment + variables from :file:`.env` and :file:`.flaskenv` files. + + If set, the :envvar:`FLASK_ENV` and :envvar:`FLASK_DEBUG` + environment variables will override :attr:`env` and + :attr:`debug`. + + Threaded mode is enabled by default. + + .. versionchanged:: 0.10 + The default port is now picked from the ``SERVER_NAME`` + variable. + """ + # Change this into a no-op if the server is invoked from the + # command line. Have a look at cli.py for more information. + if os.environ.get('FLASK_RUN_FROM_CLI') == 'true': + from .debughelpers import explain_ignored_app_run + explain_ignored_app_run() + return + + if get_load_dotenv(load_dotenv): + cli.load_dotenv() + + # if set, let env vars override previous values + if 'FLASK_ENV' in os.environ: + self.env = get_env() + self.debug = get_debug_flag() + elif 'FLASK_DEBUG' in os.environ: + self.debug = get_debug_flag() + + # debug passed to method overrides all other sources + if debug is not None: + self.debug = bool(debug) + + _host = '127.0.0.1' + _port = 5000 + server_name = self.config.get('SERVER_NAME') + sn_host, sn_port = None, None + + if server_name: + sn_host, _, sn_port = server_name.partition(':') + + host = host or sn_host or _host + port = int(port or sn_port or _port) + + options.setdefault('use_reloader', self.debug) + options.setdefault('use_debugger', self.debug) + options.setdefault('threaded', True) + + cli.show_server_banner(self.env, self.debug, self.name, False) + + from werkzeug.serving import run_simple + + try: + run_simple(host, port, self, **options) + finally: + # reset the first request information if the development server + # reset normally. This makes it possible to restart the server + # without reloader and that stuff from an interactive shell. + self._got_first_request = False + + def test_client(self, use_cookies=True, **kwargs): + """Creates a test client for this application. For information + about unit testing head over to :ref:`testing`. + + Note that if you are testing for assertions or exceptions in your + application code, you must set ``app.testing = True`` in order for the + exceptions to propagate to the test client. Otherwise, the exception + will be handled by the application (not visible to the test client) and + the only indication of an AssertionError or other exception will be a + 500 status code response to the test client. See the :attr:`testing` + attribute. For example:: + + app.testing = True + client = app.test_client() + + The test client can be used in a ``with`` block to defer the closing down + of the context until the end of the ``with`` block. This is useful if + you want to access the context locals for testing:: + + with app.test_client() as c: + rv = c.get('/?vodka=42') + assert request.args['vodka'] == '42' + + Additionally, you may pass optional keyword arguments that will then + be passed to the application's :attr:`test_client_class` constructor. + For example:: + + from flask.testing import FlaskClient + + class CustomClient(FlaskClient): + def __init__(self, *args, **kwargs): + self._authentication = kwargs.pop("authentication") + super(CustomClient,self).__init__( *args, **kwargs) + + app.test_client_class = CustomClient + client = app.test_client(authentication='Basic ....') + + See :class:`~flask.testing.FlaskClient` for more information. + + .. versionchanged:: 0.4 + added support for ``with`` block usage for the client. + + .. versionadded:: 0.7 + The `use_cookies` parameter was added as well as the ability + to override the client to be used by setting the + :attr:`test_client_class` attribute. + + .. versionchanged:: 0.11 + Added `**kwargs` to support passing additional keyword arguments to + the constructor of :attr:`test_client_class`. + """ + cls = self.test_client_class + if cls is None: + from flask.testing import FlaskClient as cls + return cls(self, self.response_class, use_cookies=use_cookies, **kwargs) + + def test_cli_runner(self, **kwargs): + """Create a CLI runner for testing CLI commands. + See :ref:`testing-cli`. + + Returns an instance of :attr:`test_cli_runner_class`, by default + :class:`~flask.testing.FlaskCliRunner`. The Flask app object is + passed as the first argument. + + .. versionadded:: 1.0 + """ + cls = self.test_cli_runner_class + + if cls is None: + from flask.testing import FlaskCliRunner as cls + + return cls(self, **kwargs) + + def open_session(self, request): + """Creates or opens a new session. Default implementation stores all + session data in a signed cookie. This requires that the + :attr:`secret_key` is set. Instead of overriding this method + we recommend replacing the :class:`session_interface`. + + .. deprecated: 1.0 + Will be removed in 1.1. Use ``session_interface.open_session`` + instead. + + :param request: an instance of :attr:`request_class`. + """ + + warnings.warn(DeprecationWarning( + '"open_session" is deprecated and will be removed in 1.1. Use' + ' "session_interface.open_session" instead.' + )) + return self.session_interface.open_session(self, request) + + def save_session(self, session, response): + """Saves the session if it needs updates. For the default + implementation, check :meth:`open_session`. Instead of overriding this + method we recommend replacing the :class:`session_interface`. + + .. deprecated: 1.0 + Will be removed in 1.1. Use ``session_interface.save_session`` + instead. + + :param session: the session to be saved (a + :class:`~werkzeug.contrib.securecookie.SecureCookie` + object) + :param response: an instance of :attr:`response_class` + """ + + warnings.warn(DeprecationWarning( + '"save_session" is deprecated and will be removed in 1.1. Use' + ' "session_interface.save_session" instead.' + )) + return self.session_interface.save_session(self, session, response) + + def make_null_session(self): + """Creates a new instance of a missing session. Instead of overriding + this method we recommend replacing the :class:`session_interface`. + + .. deprecated: 1.0 + Will be removed in 1.1. Use ``session_interface.make_null_session`` + instead. + + .. versionadded:: 0.7 + """ + + warnings.warn(DeprecationWarning( + '"make_null_session" is deprecated and will be removed in 1.1. Use' + ' "session_interface.make_null_session" instead.' + )) + return self.session_interface.make_null_session(self) + + @setupmethod + def register_blueprint(self, blueprint, **options): + """Register a :class:`~flask.Blueprint` on the application. Keyword + arguments passed to this method will override the defaults set on the + blueprint. + + Calls the blueprint's :meth:`~flask.Blueprint.register` method after + recording the blueprint in the application's :attr:`blueprints`. + + :param blueprint: The blueprint to register. + :param url_prefix: Blueprint routes will be prefixed with this. + :param subdomain: Blueprint routes will match on this subdomain. + :param url_defaults: Blueprint routes will use these default values for + view arguments. + :param options: Additional keyword arguments are passed to + :class:`~flask.blueprints.BlueprintSetupState`. They can be + accessed in :meth:`~flask.Blueprint.record` callbacks. + + .. versionadded:: 0.7 + """ + first_registration = False + + if blueprint.name in self.blueprints: + assert self.blueprints[blueprint.name] is blueprint, ( + 'A name collision occurred between blueprints %r and %r. Both' + ' share the same name "%s". Blueprints that are created on the' + ' fly need unique names.' % ( + blueprint, self.blueprints[blueprint.name], blueprint.name + ) + ) + else: + self.blueprints[blueprint.name] = blueprint + self._blueprint_order.append(blueprint) + first_registration = True + + blueprint.register(self, options, first_registration) + + def iter_blueprints(self): + """Iterates over all blueprints by the order they were registered. + + .. versionadded:: 0.11 + """ + return iter(self._blueprint_order) + + @setupmethod + def add_url_rule(self, rule, endpoint=None, view_func=None, + provide_automatic_options=None, **options): + """Connects a URL rule. Works exactly like the :meth:`route` + decorator. If a view_func is provided it will be registered with the + endpoint. + + Basically this example:: + + @app.route('/') + def index(): + pass + + Is equivalent to the following:: + + def index(): + pass + app.add_url_rule('/', 'index', index) + + If the view_func is not provided you will need to connect the endpoint + to a view function like so:: + + app.view_functions['index'] = index + + Internally :meth:`route` invokes :meth:`add_url_rule` so if you want + to customize the behavior via subclassing you only need to change + this method. + + For more information refer to :ref:`url-route-registrations`. + + .. versionchanged:: 0.2 + `view_func` parameter added. + + .. versionchanged:: 0.6 + ``OPTIONS`` is added automatically as method. + + :param rule: the URL rule as string + :param endpoint: the endpoint for the registered URL rule. Flask + itself assumes the name of the view function as + endpoint + :param view_func: the function to call when serving a request to the + provided endpoint + :param provide_automatic_options: controls whether the ``OPTIONS`` + method should be added automatically. This can also be controlled + by setting the ``view_func.provide_automatic_options = False`` + before adding the rule. + :param options: the options to be forwarded to the underlying + :class:`~werkzeug.routing.Rule` object. A change + to Werkzeug is handling of method options. methods + is a list of methods this rule should be limited + to (``GET``, ``POST`` etc.). By default a rule + just listens for ``GET`` (and implicitly ``HEAD``). + Starting with Flask 0.6, ``OPTIONS`` is implicitly + added and handled by the standard request handling. + """ + if endpoint is None: + endpoint = _endpoint_from_view_func(view_func) + options['endpoint'] = endpoint + methods = options.pop('methods', None) + + # if the methods are not given and the view_func object knows its + # methods we can use that instead. If neither exists, we go with + # a tuple of only ``GET`` as default. + if methods is None: + methods = getattr(view_func, 'methods', None) or ('GET',) + if isinstance(methods, string_types): + raise TypeError('Allowed methods have to be iterables of strings, ' + 'for example: @app.route(..., methods=["POST"])') + methods = set(item.upper() for item in methods) + + # Methods that should always be added + required_methods = set(getattr(view_func, 'required_methods', ())) + + # starting with Flask 0.8 the view_func object can disable and + # force-enable the automatic options handling. + if provide_automatic_options is None: + provide_automatic_options = getattr(view_func, + 'provide_automatic_options', None) + + if provide_automatic_options is None: + if 'OPTIONS' not in methods: + provide_automatic_options = True + required_methods.add('OPTIONS') + else: + provide_automatic_options = False + + # Add the required methods now. + methods |= required_methods + + rule = self.url_rule_class(rule, methods=methods, **options) + rule.provide_automatic_options = provide_automatic_options + + self.url_map.add(rule) + if view_func is not None: + old_func = self.view_functions.get(endpoint) + if old_func is not None and old_func != view_func: + raise AssertionError('View function mapping is overwriting an ' + 'existing endpoint function: %s' % endpoint) + self.view_functions[endpoint] = view_func + + def route(self, rule, **options): + """A decorator that is used to register a view function for a + given URL rule. This does the same thing as :meth:`add_url_rule` + but is intended for decorator usage:: + + @app.route('/') + def index(): + return 'Hello World' + + For more information refer to :ref:`url-route-registrations`. + + :param rule: the URL rule as string + :param endpoint: the endpoint for the registered URL rule. Flask + itself assumes the name of the view function as + endpoint + :param options: the options to be forwarded to the underlying + :class:`~werkzeug.routing.Rule` object. A change + to Werkzeug is handling of method options. methods + is a list of methods this rule should be limited + to (``GET``, ``POST`` etc.). By default a rule + just listens for ``GET`` (and implicitly ``HEAD``). + Starting with Flask 0.6, ``OPTIONS`` is implicitly + added and handled by the standard request handling. + """ + def decorator(f): + endpoint = options.pop('endpoint', None) + self.add_url_rule(rule, endpoint, f, **options) + return f + return decorator + + @setupmethod + def endpoint(self, endpoint): + """A decorator to register a function as an endpoint. + Example:: + + @app.endpoint('example.endpoint') + def example(): + return "example" + + :param endpoint: the name of the endpoint + """ + def decorator(f): + self.view_functions[endpoint] = f + return f + return decorator + + @staticmethod + def _get_exc_class_and_code(exc_class_or_code): + """Ensure that we register only exceptions as handler keys""" + if isinstance(exc_class_or_code, integer_types): + exc_class = default_exceptions[exc_class_or_code] + else: + exc_class = exc_class_or_code + + assert issubclass(exc_class, Exception) + + if issubclass(exc_class, HTTPException): + return exc_class, exc_class.code + else: + return exc_class, None + + @setupmethod + def errorhandler(self, code_or_exception): + """Register a function to handle errors by code or exception class. + + A decorator that is used to register a function given an + error code. Example:: + + @app.errorhandler(404) + def page_not_found(error): + return 'This page does not exist', 404 + + You can also register handlers for arbitrary exceptions:: + + @app.errorhandler(DatabaseError) + def special_exception_handler(error): + return 'Database connection failed', 500 + + .. versionadded:: 0.7 + Use :meth:`register_error_handler` instead of modifying + :attr:`error_handler_spec` directly, for application wide error + handlers. + + .. versionadded:: 0.7 + One can now additionally also register custom exception types + that do not necessarily have to be a subclass of the + :class:`~werkzeug.exceptions.HTTPException` class. + + :param code_or_exception: the code as integer for the handler, or + an arbitrary exception + """ + def decorator(f): + self._register_error_handler(None, code_or_exception, f) + return f + return decorator + + @setupmethod + def register_error_handler(self, code_or_exception, f): + """Alternative error attach function to the :meth:`errorhandler` + decorator that is more straightforward to use for non decorator + usage. + + .. versionadded:: 0.7 + """ + self._register_error_handler(None, code_or_exception, f) + + @setupmethod + def _register_error_handler(self, key, code_or_exception, f): + """ + :type key: None|str + :type code_or_exception: int|T<=Exception + :type f: callable + """ + if isinstance(code_or_exception, HTTPException): # old broken behavior + raise ValueError( + 'Tried to register a handler for an exception instance {0!r}.' + ' Handlers can only be registered for exception classes or' + ' HTTP error codes.'.format(code_or_exception) + ) + + try: + exc_class, code = self._get_exc_class_and_code(code_or_exception) + except KeyError: + raise KeyError( + "'{0}' is not a recognized HTTP error code. Use a subclass of" + " HTTPException with that code instead.".format(code_or_exception) + ) + + handlers = self.error_handler_spec.setdefault(key, {}).setdefault(code, {}) + handlers[exc_class] = f + + @setupmethod + def template_filter(self, name=None): + """A decorator that is used to register custom template filter. + You can specify a name for the filter, otherwise the function + name will be used. Example:: + + @app.template_filter() + def reverse(s): + return s[::-1] + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + def decorator(f): + self.add_template_filter(f, name=name) + return f + return decorator + + @setupmethod + def add_template_filter(self, f, name=None): + """Register a custom template filter. Works exactly like the + :meth:`template_filter` decorator. + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + self.jinja_env.filters[name or f.__name__] = f + + @setupmethod + def template_test(self, name=None): + """A decorator that is used to register custom template test. + You can specify a name for the test, otherwise the function + name will be used. Example:: + + @app.template_test() + def is_prime(n): + if n == 2: + return True + for i in range(2, int(math.ceil(math.sqrt(n))) + 1): + if n % i == 0: + return False + return True + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + def decorator(f): + self.add_template_test(f, name=name) + return f + return decorator + + @setupmethod + def add_template_test(self, f, name=None): + """Register a custom template test. Works exactly like the + :meth:`template_test` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + self.jinja_env.tests[name or f.__name__] = f + + @setupmethod + def template_global(self, name=None): + """A decorator that is used to register a custom template global function. + You can specify a name for the global function, otherwise the function + name will be used. Example:: + + @app.template_global() + def double(n): + return 2 * n + + .. versionadded:: 0.10 + + :param name: the optional name of the global function, otherwise the + function name will be used. + """ + def decorator(f): + self.add_template_global(f, name=name) + return f + return decorator + + @setupmethod + def add_template_global(self, f, name=None): + """Register a custom template global function. Works exactly like the + :meth:`template_global` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the global function, otherwise the + function name will be used. + """ + self.jinja_env.globals[name or f.__name__] = f + + @setupmethod + def before_request(self, f): + """Registers a function to run before each request. + + For example, this can be used to open a database connection, or to load + the logged in user from the session. + + The function will be called without any arguments. If it returns a + non-None value, the value is handled as if it was the return value from + the view, and further request handling is stopped. + """ + self.before_request_funcs.setdefault(None, []).append(f) + return f + + @setupmethod + def before_first_request(self, f): + """Registers a function to be run before the first request to this + instance of the application. + + The function will be called without any arguments and its return + value is ignored. + + .. versionadded:: 0.8 + """ + self.before_first_request_funcs.append(f) + return f + + @setupmethod + def after_request(self, f): + """Register a function to be run after each request. + + Your function must take one parameter, an instance of + :attr:`response_class` and return a new response object or the + same (see :meth:`process_response`). + + As of Flask 0.7 this function might not be executed at the end of the + request in case an unhandled exception occurred. + """ + self.after_request_funcs.setdefault(None, []).append(f) + return f + + @setupmethod + def teardown_request(self, f): + """Register a function to be run at the end of each request, + regardless of whether there was an exception or not. These functions + are executed when the request context is popped, even if not an + actual request was performed. + + Example:: + + ctx = app.test_request_context() + ctx.push() + ... + ctx.pop() + + When ``ctx.pop()`` is executed in the above example, the teardown + functions are called just before the request context moves from the + stack of active contexts. This becomes relevant if you are using + such constructs in tests. + + Generally teardown functions must take every necessary step to avoid + that they will fail. If they do execute code that might fail they + will have to surround the execution of these code by try/except + statements and log occurring errors. + + When a teardown function was called because of an exception it will + be passed an error object. + + The return values of teardown functions are ignored. + + .. admonition:: Debug Note + + In debug mode Flask will not tear down a request on an exception + immediately. Instead it will keep it alive so that the interactive + debugger can still access it. This behavior can be controlled + by the ``PRESERVE_CONTEXT_ON_EXCEPTION`` configuration variable. + """ + self.teardown_request_funcs.setdefault(None, []).append(f) + return f + + @setupmethod + def teardown_appcontext(self, f): + """Registers a function to be called when the application context + ends. These functions are typically also called when the request + context is popped. + + Example:: + + ctx = app.app_context() + ctx.push() + ... + ctx.pop() + + When ``ctx.pop()`` is executed in the above example, the teardown + functions are called just before the app context moves from the + stack of active contexts. This becomes relevant if you are using + such constructs in tests. + + Since a request context typically also manages an application + context it would also be called when you pop a request context. + + When a teardown function was called because of an unhandled exception + it will be passed an error object. If an :meth:`errorhandler` is + registered, it will handle the exception and the teardown will not + receive it. + + The return values of teardown functions are ignored. + + .. versionadded:: 0.9 + """ + self.teardown_appcontext_funcs.append(f) + return f + + @setupmethod + def context_processor(self, f): + """Registers a template context processor function.""" + self.template_context_processors[None].append(f) + return f + + @setupmethod + def shell_context_processor(self, f): + """Registers a shell context processor function. + + .. versionadded:: 0.11 + """ + self.shell_context_processors.append(f) + return f + + @setupmethod + def url_value_preprocessor(self, f): + """Register a URL value preprocessor function for all view + functions in the application. These functions will be called before the + :meth:`before_request` functions. + + The function can modify the values captured from the matched url before + they are passed to the view. For example, this can be used to pop a + common language code value and place it in ``g`` rather than pass it to + every view. + + The function is passed the endpoint name and values dict. The return + value is ignored. + """ + self.url_value_preprocessors.setdefault(None, []).append(f) + return f + + @setupmethod + def url_defaults(self, f): + """Callback function for URL defaults for all view functions of the + application. It's called with the endpoint and values and should + update the values passed in place. + """ + self.url_default_functions.setdefault(None, []).append(f) + return f + + def _find_error_handler(self, e): + """Return a registered error handler for an exception in this order: + blueprint handler for a specific code, app handler for a specific code, + blueprint handler for an exception class, app handler for an exception + class, or ``None`` if a suitable handler is not found. + """ + exc_class, code = self._get_exc_class_and_code(type(e)) + + for name, c in ( + (request.blueprint, code), (None, code), + (request.blueprint, None), (None, None) + ): + handler_map = self.error_handler_spec.setdefault(name, {}).get(c) + + if not handler_map: + continue + + for cls in exc_class.__mro__: + handler = handler_map.get(cls) + + if handler is not None: + return handler + + def handle_http_exception(self, e): + """Handles an HTTP exception. By default this will invoke the + registered error handlers and fall back to returning the + exception as response. + + .. versionadded:: 0.3 + """ + # Proxy exceptions don't have error codes. We want to always return + # those unchanged as errors + if e.code is None: + return e + + handler = self._find_error_handler(e) + if handler is None: + return e + return handler(e) + + def trap_http_exception(self, e): + """Checks if an HTTP exception should be trapped or not. By default + this will return ``False`` for all exceptions except for a bad request + key error if ``TRAP_BAD_REQUEST_ERRORS`` is set to ``True``. It + also returns ``True`` if ``TRAP_HTTP_EXCEPTIONS`` is set to ``True``. + + This is called for all HTTP exceptions raised by a view function. + If it returns ``True`` for any exception the error handler for this + exception is not called and it shows up as regular exception in the + traceback. This is helpful for debugging implicitly raised HTTP + exceptions. + + .. versionchanged:: 1.0 + Bad request errors are not trapped by default in debug mode. + + .. versionadded:: 0.8 + """ + if self.config['TRAP_HTTP_EXCEPTIONS']: + return True + + trap_bad_request = self.config['TRAP_BAD_REQUEST_ERRORS'] + + # if unset, trap key errors in debug mode + if ( + trap_bad_request is None and self.debug + and isinstance(e, BadRequestKeyError) + ): + return True + + if trap_bad_request: + return isinstance(e, BadRequest) + + return False + + def handle_user_exception(self, e): + """This method is called whenever an exception occurs that should be + handled. A special case are + :class:`~werkzeug.exception.HTTPException`\s which are forwarded by + this function to the :meth:`handle_http_exception` method. This + function will either return a response value or reraise the + exception with the same traceback. + + .. versionchanged:: 1.0 + Key errors raised from request data like ``form`` show the the bad + key in debug mode rather than a generic bad request message. + + .. versionadded:: 0.7 + """ + exc_type, exc_value, tb = sys.exc_info() + assert exc_value is e + # ensure not to trash sys.exc_info() at that point in case someone + # wants the traceback preserved in handle_http_exception. Of course + # we cannot prevent users from trashing it themselves in a custom + # trap_http_exception method so that's their fault then. + + # MultiDict passes the key to the exception, but that's ignored + # when generating the response message. Set an informative + # description for key errors in debug mode or when trapping errors. + if ( + (self.debug or self.config['TRAP_BAD_REQUEST_ERRORS']) + and isinstance(e, BadRequestKeyError) + # only set it if it's still the default description + and e.description is BadRequestKeyError.description + ): + e.description = "KeyError: '{0}'".format(*e.args) + + if isinstance(e, HTTPException) and not self.trap_http_exception(e): + return self.handle_http_exception(e) + + handler = self._find_error_handler(e) + + if handler is None: + reraise(exc_type, exc_value, tb) + return handler(e) + + def handle_exception(self, e): + """Default exception handling that kicks in when an exception + occurs that is not caught. In debug mode the exception will + be re-raised immediately, otherwise it is logged and the handler + for a 500 internal server error is used. If no such handler + exists, a default 500 internal server error message is displayed. + + .. versionadded:: 0.3 + """ + exc_type, exc_value, tb = sys.exc_info() + + got_request_exception.send(self, exception=e) + handler = self._find_error_handler(InternalServerError()) + + if self.propagate_exceptions: + # if we want to repropagate the exception, we can attempt to + # raise it with the whole traceback in case we can do that + # (the function was actually called from the except part) + # otherwise, we just raise the error again + if exc_value is e: + reraise(exc_type, exc_value, tb) + else: + raise e + + self.log_exception((exc_type, exc_value, tb)) + if handler is None: + return InternalServerError() + return self.finalize_request(handler(e), from_error_handler=True) + + def log_exception(self, exc_info): + """Logs an exception. This is called by :meth:`handle_exception` + if debugging is disabled and right before the handler is called. + The default implementation logs the exception as error on the + :attr:`logger`. + + .. versionadded:: 0.8 + """ + self.logger.error('Exception on %s [%s]' % ( + request.path, + request.method + ), exc_info=exc_info) + + def raise_routing_exception(self, request): + """Exceptions that are recording during routing are reraised with + this method. During debug we are not reraising redirect requests + for non ``GET``, ``HEAD``, or ``OPTIONS`` requests and we're raising + a different error instead to help debug situations. + + :internal: + """ + if not self.debug \ + or not isinstance(request.routing_exception, RequestRedirect) \ + or request.method in ('GET', 'HEAD', 'OPTIONS'): + raise request.routing_exception + + from .debughelpers import FormDataRoutingRedirect + raise FormDataRoutingRedirect(request) + + def dispatch_request(self): + """Does the request dispatching. Matches the URL and returns the + return value of the view or error handler. This does not have to + be a response object. In order to convert the return value to a + proper response object, call :func:`make_response`. + + .. versionchanged:: 0.7 + This no longer does the exception handling, this code was + moved to the new :meth:`full_dispatch_request`. + """ + req = _request_ctx_stack.top.request + if req.routing_exception is not None: + self.raise_routing_exception(req) + rule = req.url_rule + # if we provide automatic options for this URL and the + # request came with the OPTIONS method, reply automatically + if getattr(rule, 'provide_automatic_options', False) \ + and req.method == 'OPTIONS': + return self.make_default_options_response() + # otherwise dispatch to the handler for that endpoint + return self.view_functions[rule.endpoint](**req.view_args) + + def full_dispatch_request(self): + """Dispatches the request and on top of that performs request + pre and postprocessing as well as HTTP exception catching and + error handling. + + .. versionadded:: 0.7 + """ + self.try_trigger_before_first_request_functions() + try: + request_started.send(self) + rv = self.preprocess_request() + if rv is None: + rv = self.dispatch_request() + except Exception as e: + rv = self.handle_user_exception(e) + return self.finalize_request(rv) + + def finalize_request(self, rv, from_error_handler=False): + """Given the return value from a view function this finalizes + the request by converting it into a response and invoking the + postprocessing functions. This is invoked for both normal + request dispatching as well as error handlers. + + Because this means that it might be called as a result of a + failure a special safe mode is available which can be enabled + with the `from_error_handler` flag. If enabled, failures in + response processing will be logged and otherwise ignored. + + :internal: + """ + response = self.make_response(rv) + try: + response = self.process_response(response) + request_finished.send(self, response=response) + except Exception: + if not from_error_handler: + raise + self.logger.exception('Request finalizing failed with an ' + 'error while handling an error') + return response + + def try_trigger_before_first_request_functions(self): + """Called before each request and will ensure that it triggers + the :attr:`before_first_request_funcs` and only exactly once per + application instance (which means process usually). + + :internal: + """ + if self._got_first_request: + return + with self._before_request_lock: + if self._got_first_request: + return + for func in self.before_first_request_funcs: + func() + self._got_first_request = True + + def make_default_options_response(self): + """This method is called to create the default ``OPTIONS`` response. + This can be changed through subclassing to change the default + behavior of ``OPTIONS`` responses. + + .. versionadded:: 0.7 + """ + adapter = _request_ctx_stack.top.url_adapter + if hasattr(adapter, 'allowed_methods'): + methods = adapter.allowed_methods() + else: + # fallback for Werkzeug < 0.7 + methods = [] + try: + adapter.match(method='--') + except MethodNotAllowed as e: + methods = e.valid_methods + except HTTPException as e: + pass + rv = self.response_class() + rv.allow.update(methods) + return rv + + def should_ignore_error(self, error): + """This is called to figure out if an error should be ignored + or not as far as the teardown system is concerned. If this + function returns ``True`` then the teardown handlers will not be + passed the error. + + .. versionadded:: 0.10 + """ + return False + + def make_response(self, rv): + """Convert the return value from a view function to an instance of + :attr:`response_class`. + + :param rv: the return value from the view function. The view function + must return a response. Returning ``None``, or the view ending + without returning, is not allowed. The following types are allowed + for ``view_rv``: + + ``str`` (``unicode`` in Python 2) + A response object is created with the string encoded to UTF-8 + as the body. + + ``bytes`` (``str`` in Python 2) + A response object is created with the bytes as the body. + + ``tuple`` + Either ``(body, status, headers)``, ``(body, status)``, or + ``(body, headers)``, where ``body`` is any of the other types + allowed here, ``status`` is a string or an integer, and + ``headers`` is a dictionary or a list of ``(key, value)`` + tuples. If ``body`` is a :attr:`response_class` instance, + ``status`` overwrites the exiting value and ``headers`` are + extended. + + :attr:`response_class` + The object is returned unchanged. + + other :class:`~werkzeug.wrappers.Response` class + The object is coerced to :attr:`response_class`. + + :func:`callable` + The function is called as a WSGI application. The result is + used to create a response object. + + .. versionchanged:: 0.9 + Previously a tuple was interpreted as the arguments for the + response object. + """ + + status = headers = None + + # unpack tuple returns + if isinstance(rv, tuple): + len_rv = len(rv) + + # a 3-tuple is unpacked directly + if len_rv == 3: + rv, status, headers = rv + # decide if a 2-tuple has status or headers + elif len_rv == 2: + if isinstance(rv[1], (Headers, dict, tuple, list)): + rv, headers = rv + else: + rv, status = rv + # other sized tuples are not allowed + else: + raise TypeError( + 'The view function did not return a valid response tuple.' + ' The tuple must have the form (body, status, headers),' + ' (body, status), or (body, headers).' + ) + + # the body must not be None + if rv is None: + raise TypeError( + 'The view function did not return a valid response. The' + ' function either returned None or ended without a return' + ' statement.' + ) + + # make sure the body is an instance of the response class + if not isinstance(rv, self.response_class): + if isinstance(rv, (text_type, bytes, bytearray)): + # let the response class set the status and headers instead of + # waiting to do it manually, so that the class can handle any + # special logic + rv = self.response_class(rv, status=status, headers=headers) + status = headers = None + else: + # evaluate a WSGI callable, or coerce a different response + # class to the correct type + try: + rv = self.response_class.force_type(rv, request.environ) + except TypeError as e: + new_error = TypeError( + '{e}\nThe view function did not return a valid' + ' response. The return type must be a string, tuple,' + ' Response instance, or WSGI callable, but it was a' + ' {rv.__class__.__name__}.'.format(e=e, rv=rv) + ) + reraise(TypeError, new_error, sys.exc_info()[2]) + + # prefer the status if it was provided + if status is not None: + if isinstance(status, (text_type, bytes, bytearray)): + rv.status = status + else: + rv.status_code = status + + # extend existing headers with provided headers + if headers: + rv.headers.extend(headers) + + return rv + + def create_url_adapter(self, request): + """Creates a URL adapter for the given request. The URL adapter + is created at a point where the request context is not yet set + up so the request is passed explicitly. + + .. versionadded:: 0.6 + + .. versionchanged:: 0.9 + This can now also be called without a request object when the + URL adapter is created for the application context. + + .. versionchanged:: 1.0 + :data:`SERVER_NAME` no longer implicitly enables subdomain + matching. Use :attr:`subdomain_matching` instead. + """ + if request is not None: + # If subdomain matching is disabled (the default), use the + # default subdomain in all cases. This should be the default + # in Werkzeug but it currently does not have that feature. + subdomain = ((self.url_map.default_subdomain or None) + if not self.subdomain_matching else None) + return self.url_map.bind_to_environ( + request.environ, + server_name=self.config['SERVER_NAME'], + subdomain=subdomain) + # We need at the very least the server name to be set for this + # to work. + if self.config['SERVER_NAME'] is not None: + return self.url_map.bind( + self.config['SERVER_NAME'], + script_name=self.config['APPLICATION_ROOT'], + url_scheme=self.config['PREFERRED_URL_SCHEME']) + + def inject_url_defaults(self, endpoint, values): + """Injects the URL defaults for the given endpoint directly into + the values dictionary passed. This is used internally and + automatically called on URL building. + + .. versionadded:: 0.7 + """ + funcs = self.url_default_functions.get(None, ()) + if '.' in endpoint: + bp = endpoint.rsplit('.', 1)[0] + funcs = chain(funcs, self.url_default_functions.get(bp, ())) + for func in funcs: + func(endpoint, values) + + def handle_url_build_error(self, error, endpoint, values): + """Handle :class:`~werkzeug.routing.BuildError` on :meth:`url_for`. + """ + exc_type, exc_value, tb = sys.exc_info() + for handler in self.url_build_error_handlers: + try: + rv = handler(error, endpoint, values) + if rv is not None: + return rv + except BuildError as e: + # make error available outside except block (py3) + error = e + + # At this point we want to reraise the exception. If the error is + # still the same one we can reraise it with the original traceback, + # otherwise we raise it from here. + if error is exc_value: + reraise(exc_type, exc_value, tb) + raise error + + def preprocess_request(self): + """Called before the request is dispatched. Calls + :attr:`url_value_preprocessors` registered with the app and the + current blueprint (if any). Then calls :attr:`before_request_funcs` + registered with the app and the blueprint. + + If any :meth:`before_request` handler returns a non-None value, the + value is handled as if it was the return value from the view, and + further request handling is stopped. + """ + + bp = _request_ctx_stack.top.request.blueprint + + funcs = self.url_value_preprocessors.get(None, ()) + if bp is not None and bp in self.url_value_preprocessors: + funcs = chain(funcs, self.url_value_preprocessors[bp]) + for func in funcs: + func(request.endpoint, request.view_args) + + funcs = self.before_request_funcs.get(None, ()) + if bp is not None and bp in self.before_request_funcs: + funcs = chain(funcs, self.before_request_funcs[bp]) + for func in funcs: + rv = func() + if rv is not None: + return rv + + def process_response(self, response): + """Can be overridden in order to modify the response object + before it's sent to the WSGI server. By default this will + call all the :meth:`after_request` decorated functions. + + .. versionchanged:: 0.5 + As of Flask 0.5 the functions registered for after request + execution are called in reverse order of registration. + + :param response: a :attr:`response_class` object. + :return: a new response object or the same, has to be an + instance of :attr:`response_class`. + """ + ctx = _request_ctx_stack.top + bp = ctx.request.blueprint + funcs = ctx._after_request_functions + if bp is not None and bp in self.after_request_funcs: + funcs = chain(funcs, reversed(self.after_request_funcs[bp])) + if None in self.after_request_funcs: + funcs = chain(funcs, reversed(self.after_request_funcs[None])) + for handler in funcs: + response = handler(response) + if not self.session_interface.is_null_session(ctx.session): + self.session_interface.save_session(self, ctx.session, response) + return response + + def do_teardown_request(self, exc=_sentinel): + """Called after the request is dispatched and the response is + returned, right before the request context is popped. + + This calls all functions decorated with + :meth:`teardown_request`, and :meth:`Blueprint.teardown_request` + if a blueprint handled the request. Finally, the + :data:`request_tearing_down` signal is sent. + + This is called by + :meth:`RequestContext.pop() `, + which may be delayed during testing to maintain access to + resources. + + :param exc: An unhandled exception raised while dispatching the + request. Detected from the current exception information if + not passed. Passed to each teardown function. + + .. versionchanged:: 0.9 + Added the ``exc`` argument. + """ + if exc is _sentinel: + exc = sys.exc_info()[1] + funcs = reversed(self.teardown_request_funcs.get(None, ())) + bp = _request_ctx_stack.top.request.blueprint + if bp is not None and bp in self.teardown_request_funcs: + funcs = chain(funcs, reversed(self.teardown_request_funcs[bp])) + for func in funcs: + func(exc) + request_tearing_down.send(self, exc=exc) + + def do_teardown_appcontext(self, exc=_sentinel): + """Called right before the application context is popped. + + When handling a request, the application context is popped + after the request context. See :meth:`do_teardown_request`. + + This calls all functions decorated with + :meth:`teardown_appcontext`. Then the + :data:`appcontext_tearing_down` signal is sent. + + This is called by + :meth:`AppContext.pop() `. + + .. versionadded:: 0.9 + """ + if exc is _sentinel: + exc = sys.exc_info()[1] + for func in reversed(self.teardown_appcontext_funcs): + func(exc) + appcontext_tearing_down.send(self, exc=exc) + + def app_context(self): + """Create an :class:`~flask.ctx.AppContext`. Use as a ``with`` + block to push the context, which will make :data:`current_app` + point at this application. + + An application context is automatically pushed by + :meth:`RequestContext.push() ` + when handling a request, and when running a CLI command. Use + this to manually create a context outside of these situations. + + :: + + with app.app_context(): + init_db() + + See :doc:`/appcontext`. + + .. versionadded:: 0.9 + """ + return AppContext(self) + + def request_context(self, environ): + """Create a :class:`~flask.ctx.RequestContext` representing a + WSGI environment. Use a ``with`` block to push the context, + which will make :data:`request` point at this request. + + See :doc:`/reqcontext`. + + Typically you should not call this from your own code. A request + context is automatically pushed by the :meth:`wsgi_app` when + handling a request. Use :meth:`test_request_context` to create + an environment and context instead of this method. + + :param environ: a WSGI environment + """ + return RequestContext(self, environ) + + def test_request_context(self, *args, **kwargs): + """Create a :class:`~flask.ctx.RequestContext` for a WSGI + environment created from the given values. This is mostly useful + during testing, where you may want to run a function that uses + request data without dispatching a full request. + + See :doc:`/reqcontext`. + + Use a ``with`` block to push the context, which will make + :data:`request` point at the request for the created + environment. :: + + with test_request_context(...): + generate_report() + + When using the shell, it may be easier to push and pop the + context manually to avoid indentation. :: + + ctx = app.test_request_context(...) + ctx.push() + ... + ctx.pop() + + Takes the same arguments as Werkzeug's + :class:`~werkzeug.test.EnvironBuilder`, with some defaults from + the application. See the linked Werkzeug docs for most of the + available arguments. Flask-specific behavior is listed here. + + :param path: URL path being requested. + :param base_url: Base URL where the app is being served, which + ``path`` is relative to. If not given, built from + :data:`PREFERRED_URL_SCHEME`, ``subdomain``, + :data:`SERVER_NAME`, and :data:`APPLICATION_ROOT`. + :param subdomain: Subdomain name to append to + :data:`SERVER_NAME`. + :param url_scheme: Scheme to use instead of + :data:`PREFERRED_URL_SCHEME`. + :param data: The request body, either as a string or a dict of + form keys and values. + :param json: If given, this is serialized as JSON and passed as + ``data``. Also defaults ``content_type`` to + ``application/json``. + :param args: other positional arguments passed to + :class:`~werkzeug.test.EnvironBuilder`. + :param kwargs: other keyword arguments passed to + :class:`~werkzeug.test.EnvironBuilder`. + """ + from flask.testing import make_test_environ_builder + + builder = make_test_environ_builder(self, *args, **kwargs) + + try: + return self.request_context(builder.get_environ()) + finally: + builder.close() + + def wsgi_app(self, environ, start_response): + """The actual WSGI application. This is not implemented in + :meth:`__call__` so that middlewares can be applied without + losing a reference to the app object. Instead of doing this:: + + app = MyMiddleware(app) + + It's a better idea to do this instead:: + + app.wsgi_app = MyMiddleware(app.wsgi_app) + + Then you still have the original application object around and + can continue to call methods on it. + + .. versionchanged:: 0.7 + Teardown events for the request and app contexts are called + even if an unhandled error occurs. Other events may not be + called depending on when an error occurs during dispatch. + See :ref:`callbacks-and-errors`. + + :param environ: A WSGI environment. + :param start_response: A callable accepting a status code, + a list of headers, and an optional exception context to + start the response. + """ + ctx = self.request_context(environ) + error = None + try: + try: + ctx.push() + response = self.full_dispatch_request() + except Exception as e: + error = e + response = self.handle_exception(e) + except: + error = sys.exc_info()[1] + raise + return response(environ, start_response) + finally: + if self.should_ignore_error(error): + error = None + ctx.auto_pop(error) + + def __call__(self, environ, start_response): + """The WSGI server calls the Flask application object as the + WSGI application. This calls :meth:`wsgi_app` which can be + wrapped to applying middleware.""" + return self.wsgi_app(environ, start_response) + + def __repr__(self): + return '<%s %r>' % ( + self.__class__.__name__, + self.name, + ) diff --git a/pyextra/flask/blueprints.py b/pyextra/flask/blueprints.py new file mode 100644 index 00000000000000..5ce5561e4e1950 --- /dev/null +++ b/pyextra/flask/blueprints.py @@ -0,0 +1,448 @@ +# -*- coding: utf-8 -*- +""" + flask.blueprints + ~~~~~~~~~~~~~~~~ + + Blueprints are the recommended way to implement larger or more + pluggable applications in Flask 0.7 and later. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" +from functools import update_wrapper +from werkzeug.urls import url_join + +from .helpers import _PackageBoundObject, _endpoint_from_view_func + + +class BlueprintSetupState(object): + """Temporary holder object for registering a blueprint with the + application. An instance of this class is created by the + :meth:`~flask.Blueprint.make_setup_state` method and later passed + to all register callback functions. + """ + + def __init__(self, blueprint, app, options, first_registration): + #: a reference to the current application + self.app = app + + #: a reference to the blueprint that created this setup state. + self.blueprint = blueprint + + #: a dictionary with all options that were passed to the + #: :meth:`~flask.Flask.register_blueprint` method. + self.options = options + + #: as blueprints can be registered multiple times with the + #: application and not everything wants to be registered + #: multiple times on it, this attribute can be used to figure + #: out if the blueprint was registered in the past already. + self.first_registration = first_registration + + subdomain = self.options.get('subdomain') + if subdomain is None: + subdomain = self.blueprint.subdomain + + #: The subdomain that the blueprint should be active for, ``None`` + #: otherwise. + self.subdomain = subdomain + + url_prefix = self.options.get('url_prefix') + if url_prefix is None: + url_prefix = self.blueprint.url_prefix + #: The prefix that should be used for all URLs defined on the + #: blueprint. + self.url_prefix = url_prefix + + #: A dictionary with URL defaults that is added to each and every + #: URL that was defined with the blueprint. + self.url_defaults = dict(self.blueprint.url_values_defaults) + self.url_defaults.update(self.options.get('url_defaults', ())) + + def add_url_rule(self, rule, endpoint=None, view_func=None, **options): + """A helper method to register a rule (and optionally a view function) + to the application. The endpoint is automatically prefixed with the + blueprint's name. + """ + if self.url_prefix is not None: + if rule: + rule = '/'.join(( + self.url_prefix.rstrip('/'), rule.lstrip('/'))) + else: + rule = self.url_prefix + options.setdefault('subdomain', self.subdomain) + if endpoint is None: + endpoint = _endpoint_from_view_func(view_func) + defaults = self.url_defaults + if 'defaults' in options: + defaults = dict(defaults, **options.pop('defaults')) + self.app.add_url_rule(rule, '%s.%s' % (self.blueprint.name, endpoint), + view_func, defaults=defaults, **options) + + +class Blueprint(_PackageBoundObject): + """Represents a blueprint. A blueprint is an object that records + functions that will be called with the + :class:`~flask.blueprints.BlueprintSetupState` later to register functions + or other things on the main application. See :ref:`blueprints` for more + information. + + .. versionadded:: 0.7 + """ + + warn_on_modifications = False + _got_registered_once = False + + #: Blueprint local JSON decoder class to use. + #: Set to ``None`` to use the app's :class:`~flask.app.Flask.json_encoder`. + json_encoder = None + #: Blueprint local JSON decoder class to use. + #: Set to ``None`` to use the app's :class:`~flask.app.Flask.json_decoder`. + json_decoder = None + + # TODO remove the next three attrs when Sphinx :inherited-members: works + # https://github.com/sphinx-doc/sphinx/issues/741 + + #: The name of the package or module that this app belongs to. Do not + #: change this once it is set by the constructor. + import_name = None + + #: Location of the template files to be added to the template lookup. + #: ``None`` if templates should not be added. + template_folder = None + + #: Absolute path to the package on the filesystem. Used to look up + #: resources contained in the package. + root_path = None + + def __init__(self, name, import_name, static_folder=None, + static_url_path=None, template_folder=None, + url_prefix=None, subdomain=None, url_defaults=None, + root_path=None): + _PackageBoundObject.__init__(self, import_name, template_folder, + root_path=root_path) + self.name = name + self.url_prefix = url_prefix + self.subdomain = subdomain + self.static_folder = static_folder + self.static_url_path = static_url_path + self.deferred_functions = [] + if url_defaults is None: + url_defaults = {} + self.url_values_defaults = url_defaults + + def record(self, func): + """Registers a function that is called when the blueprint is + registered on the application. This function is called with the + state as argument as returned by the :meth:`make_setup_state` + method. + """ + if self._got_registered_once and self.warn_on_modifications: + from warnings import warn + warn(Warning('The blueprint was already registered once ' + 'but is getting modified now. These changes ' + 'will not show up.')) + self.deferred_functions.append(func) + + def record_once(self, func): + """Works like :meth:`record` but wraps the function in another + function that will ensure the function is only called once. If the + blueprint is registered a second time on the application, the + function passed is not called. + """ + def wrapper(state): + if state.first_registration: + func(state) + return self.record(update_wrapper(wrapper, func)) + + def make_setup_state(self, app, options, first_registration=False): + """Creates an instance of :meth:`~flask.blueprints.BlueprintSetupState` + object that is later passed to the register callback functions. + Subclasses can override this to return a subclass of the setup state. + """ + return BlueprintSetupState(self, app, options, first_registration) + + def register(self, app, options, first_registration=False): + """Called by :meth:`Flask.register_blueprint` to register all views + and callbacks registered on the blueprint with the application. Creates + a :class:`.BlueprintSetupState` and calls each :meth:`record` callback + with it. + + :param app: The application this blueprint is being registered with. + :param options: Keyword arguments forwarded from + :meth:`~Flask.register_blueprint`. + :param first_registration: Whether this is the first time this + blueprint has been registered on the application. + """ + self._got_registered_once = True + state = self.make_setup_state(app, options, first_registration) + + if self.has_static_folder: + state.add_url_rule( + self.static_url_path + '/', + view_func=self.send_static_file, endpoint='static' + ) + + for deferred in self.deferred_functions: + deferred(state) + + def route(self, rule, **options): + """Like :meth:`Flask.route` but for a blueprint. The endpoint for the + :func:`url_for` function is prefixed with the name of the blueprint. + """ + def decorator(f): + endpoint = options.pop("endpoint", f.__name__) + self.add_url_rule(rule, endpoint, f, **options) + return f + return decorator + + def add_url_rule(self, rule, endpoint=None, view_func=None, **options): + """Like :meth:`Flask.add_url_rule` but for a blueprint. The endpoint for + the :func:`url_for` function is prefixed with the name of the blueprint. + """ + if endpoint: + assert '.' not in endpoint, "Blueprint endpoints should not contain dots" + if view_func and hasattr(view_func, '__name__'): + assert '.' not in view_func.__name__, "Blueprint view function name should not contain dots" + self.record(lambda s: + s.add_url_rule(rule, endpoint, view_func, **options)) + + def endpoint(self, endpoint): + """Like :meth:`Flask.endpoint` but for a blueprint. This does not + prefix the endpoint with the blueprint name, this has to be done + explicitly by the user of this method. If the endpoint is prefixed + with a `.` it will be registered to the current blueprint, otherwise + it's an application independent endpoint. + """ + def decorator(f): + def register_endpoint(state): + state.app.view_functions[endpoint] = f + self.record_once(register_endpoint) + return f + return decorator + + def app_template_filter(self, name=None): + """Register a custom template filter, available application wide. Like + :meth:`Flask.template_filter` but for a blueprint. + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + def decorator(f): + self.add_app_template_filter(f, name=name) + return f + return decorator + + def add_app_template_filter(self, f, name=None): + """Register a custom template filter, available application wide. Like + :meth:`Flask.add_template_filter` but for a blueprint. Works exactly + like the :meth:`app_template_filter` decorator. + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + def register_template(state): + state.app.jinja_env.filters[name or f.__name__] = f + self.record_once(register_template) + + def app_template_test(self, name=None): + """Register a custom template test, available application wide. Like + :meth:`Flask.template_test` but for a blueprint. + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + def decorator(f): + self.add_app_template_test(f, name=name) + return f + return decorator + + def add_app_template_test(self, f, name=None): + """Register a custom template test, available application wide. Like + :meth:`Flask.add_template_test` but for a blueprint. Works exactly + like the :meth:`app_template_test` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + def register_template(state): + state.app.jinja_env.tests[name or f.__name__] = f + self.record_once(register_template) + + def app_template_global(self, name=None): + """Register a custom template global, available application wide. Like + :meth:`Flask.template_global` but for a blueprint. + + .. versionadded:: 0.10 + + :param name: the optional name of the global, otherwise the + function name will be used. + """ + def decorator(f): + self.add_app_template_global(f, name=name) + return f + return decorator + + def add_app_template_global(self, f, name=None): + """Register a custom template global, available application wide. Like + :meth:`Flask.add_template_global` but for a blueprint. Works exactly + like the :meth:`app_template_global` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the global, otherwise the + function name will be used. + """ + def register_template(state): + state.app.jinja_env.globals[name or f.__name__] = f + self.record_once(register_template) + + def before_request(self, f): + """Like :meth:`Flask.before_request` but for a blueprint. This function + is only executed before each request that is handled by a function of + that blueprint. + """ + self.record_once(lambda s: s.app.before_request_funcs + .setdefault(self.name, []).append(f)) + return f + + def before_app_request(self, f): + """Like :meth:`Flask.before_request`. Such a function is executed + before each request, even if outside of a blueprint. + """ + self.record_once(lambda s: s.app.before_request_funcs + .setdefault(None, []).append(f)) + return f + + def before_app_first_request(self, f): + """Like :meth:`Flask.before_first_request`. Such a function is + executed before the first request to the application. + """ + self.record_once(lambda s: s.app.before_first_request_funcs.append(f)) + return f + + def after_request(self, f): + """Like :meth:`Flask.after_request` but for a blueprint. This function + is only executed after each request that is handled by a function of + that blueprint. + """ + self.record_once(lambda s: s.app.after_request_funcs + .setdefault(self.name, []).append(f)) + return f + + def after_app_request(self, f): + """Like :meth:`Flask.after_request` but for a blueprint. Such a function + is executed after each request, even if outside of the blueprint. + """ + self.record_once(lambda s: s.app.after_request_funcs + .setdefault(None, []).append(f)) + return f + + def teardown_request(self, f): + """Like :meth:`Flask.teardown_request` but for a blueprint. This + function is only executed when tearing down requests handled by a + function of that blueprint. Teardown request functions are executed + when the request context is popped, even when no actual request was + performed. + """ + self.record_once(lambda s: s.app.teardown_request_funcs + .setdefault(self.name, []).append(f)) + return f + + def teardown_app_request(self, f): + """Like :meth:`Flask.teardown_request` but for a blueprint. Such a + function is executed when tearing down each request, even if outside of + the blueprint. + """ + self.record_once(lambda s: s.app.teardown_request_funcs + .setdefault(None, []).append(f)) + return f + + def context_processor(self, f): + """Like :meth:`Flask.context_processor` but for a blueprint. This + function is only executed for requests handled by a blueprint. + """ + self.record_once(lambda s: s.app.template_context_processors + .setdefault(self.name, []).append(f)) + return f + + def app_context_processor(self, f): + """Like :meth:`Flask.context_processor` but for a blueprint. Such a + function is executed each request, even if outside of the blueprint. + """ + self.record_once(lambda s: s.app.template_context_processors + .setdefault(None, []).append(f)) + return f + + def app_errorhandler(self, code): + """Like :meth:`Flask.errorhandler` but for a blueprint. This + handler is used for all requests, even if outside of the blueprint. + """ + def decorator(f): + self.record_once(lambda s: s.app.errorhandler(code)(f)) + return f + return decorator + + def url_value_preprocessor(self, f): + """Registers a function as URL value preprocessor for this + blueprint. It's called before the view functions are called and + can modify the url values provided. + """ + self.record_once(lambda s: s.app.url_value_preprocessors + .setdefault(self.name, []).append(f)) + return f + + def url_defaults(self, f): + """Callback function for URL defaults for this blueprint. It's called + with the endpoint and values and should update the values passed + in place. + """ + self.record_once(lambda s: s.app.url_default_functions + .setdefault(self.name, []).append(f)) + return f + + def app_url_value_preprocessor(self, f): + """Same as :meth:`url_value_preprocessor` but application wide. + """ + self.record_once(lambda s: s.app.url_value_preprocessors + .setdefault(None, []).append(f)) + return f + + def app_url_defaults(self, f): + """Same as :meth:`url_defaults` but application wide. + """ + self.record_once(lambda s: s.app.url_default_functions + .setdefault(None, []).append(f)) + return f + + def errorhandler(self, code_or_exception): + """Registers an error handler that becomes active for this blueprint + only. Please be aware that routing does not happen local to a + blueprint so an error handler for 404 usually is not handled by + a blueprint unless it is caused inside a view function. Another + special case is the 500 internal server error which is always looked + up from the application. + + Otherwise works as the :meth:`~flask.Flask.errorhandler` decorator + of the :class:`~flask.Flask` object. + """ + def decorator(f): + self.record_once(lambda s: s.app._register_error_handler( + self.name, code_or_exception, f)) + return f + return decorator + + def register_error_handler(self, code_or_exception, f): + """Non-decorator version of the :meth:`errorhandler` error attach + function, akin to the :meth:`~flask.Flask.register_error_handler` + application-wide function of the :class:`~flask.Flask` object but + for error handlers limited to this blueprint. + + .. versionadded:: 0.11 + """ + self.record_once(lambda s: s.app._register_error_handler( + self.name, code_or_exception, f)) diff --git a/pyextra/flask/cli.py b/pyextra/flask/cli.py new file mode 100644 index 00000000000000..efc1733e29cb86 --- /dev/null +++ b/pyextra/flask/cli.py @@ -0,0 +1,898 @@ +# -*- coding: utf-8 -*- +""" + flask.cli + ~~~~~~~~~ + + A simple command line application to run flask apps. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +from __future__ import print_function + +import ast +import inspect +import os +import re +import ssl +import sys +import traceback +from functools import update_wrapper +from operator import attrgetter +from threading import Lock, Thread + +import click +from werkzeug.utils import import_string + +from . import __version__ +from ._compat import getargspec, iteritems, reraise, text_type +from .globals import current_app +from .helpers import get_debug_flag, get_env, get_load_dotenv + +try: + import dotenv +except ImportError: + dotenv = None + + +class NoAppException(click.UsageError): + """Raised if an application cannot be found or loaded.""" + + +def find_best_app(script_info, module): + """Given a module instance this tries to find the best possible + application in the module or raises an exception. + """ + from . import Flask + + # Search for the most common names first. + for attr_name in ('app', 'application'): + app = getattr(module, attr_name, None) + + if isinstance(app, Flask): + return app + + # Otherwise find the only object that is a Flask instance. + matches = [ + v for k, v in iteritems(module.__dict__) if isinstance(v, Flask) + ] + + if len(matches) == 1: + return matches[0] + elif len(matches) > 1: + raise NoAppException( + 'Detected multiple Flask applications in module "{module}". Use ' + '"FLASK_APP={module}:name" to specify the correct ' + 'one.'.format(module=module.__name__) + ) + + # Search for app factory functions. + for attr_name in ('create_app', 'make_app'): + app_factory = getattr(module, attr_name, None) + + if inspect.isfunction(app_factory): + try: + app = call_factory(script_info, app_factory) + + if isinstance(app, Flask): + return app + except TypeError: + if not _called_with_wrong_args(app_factory): + raise + raise NoAppException( + 'Detected factory "{factory}" in module "{module}", but ' + 'could not call it without arguments. Use ' + '"FLASK_APP=\'{module}:{factory}(args)\'" to specify ' + 'arguments.'.format( + factory=attr_name, module=module.__name__ + ) + ) + + raise NoAppException( + 'Failed to find Flask application or factory in module "{module}". ' + 'Use "FLASK_APP={module}:name to specify one.'.format( + module=module.__name__ + ) + ) + + +def call_factory(script_info, app_factory, arguments=()): + """Takes an app factory, a ``script_info` object and optionally a tuple + of arguments. Checks for the existence of a script_info argument and calls + the app_factory depending on that and the arguments provided. + """ + args_spec = getargspec(app_factory) + arg_names = args_spec.args + arg_defaults = args_spec.defaults + + if 'script_info' in arg_names: + return app_factory(*arguments, script_info=script_info) + elif arguments: + return app_factory(*arguments) + elif not arguments and len(arg_names) == 1 and arg_defaults is None: + return app_factory(script_info) + + return app_factory() + + +def _called_with_wrong_args(factory): + """Check whether calling a function raised a ``TypeError`` because + the call failed or because something in the factory raised the + error. + + :param factory: the factory function that was called + :return: true if the call failed + """ + tb = sys.exc_info()[2] + + try: + while tb is not None: + if tb.tb_frame.f_code is factory.__code__: + # in the factory, it was called successfully + return False + + tb = tb.tb_next + + # didn't reach the factory + return True + finally: + del tb + + +def find_app_by_string(script_info, module, app_name): + """Checks if the given string is a variable name or a function. If it is a + function, it checks for specified arguments and whether it takes a + ``script_info`` argument and calls the function with the appropriate + arguments. + """ + from flask import Flask + match = re.match(r'^ *([^ ()]+) *(?:\((.*?) *,? *\))? *$', app_name) + + if not match: + raise NoAppException( + '"{name}" is not a valid variable name or function ' + 'expression.'.format(name=app_name) + ) + + name, args = match.groups() + + try: + attr = getattr(module, name) + except AttributeError as e: + raise NoAppException(e.args[0]) + + if inspect.isfunction(attr): + if args: + try: + args = ast.literal_eval('({args},)'.format(args=args)) + except (ValueError, SyntaxError)as e: + raise NoAppException( + 'Could not parse the arguments in ' + '"{app_name}".'.format(e=e, app_name=app_name) + ) + else: + args = () + + try: + app = call_factory(script_info, attr, args) + except TypeError as e: + if not _called_with_wrong_args(attr): + raise + + raise NoAppException( + '{e}\nThe factory "{app_name}" in module "{module}" could not ' + 'be called with the specified arguments.'.format( + e=e, app_name=app_name, module=module.__name__ + ) + ) + else: + app = attr + + if isinstance(app, Flask): + return app + + raise NoAppException( + 'A valid Flask application was not obtained from ' + '"{module}:{app_name}".'.format( + module=module.__name__, app_name=app_name + ) + ) + + +def prepare_import(path): + """Given a filename this will try to calculate the python path, add it + to the search path and return the actual module name that is expected. + """ + path = os.path.realpath(path) + + if os.path.splitext(path)[1] == '.py': + path = os.path.splitext(path)[0] + + if os.path.basename(path) == '__init__': + path = os.path.dirname(path) + + module_name = [] + + # move up until outside package structure (no __init__.py) + while True: + path, name = os.path.split(path) + module_name.append(name) + + if not os.path.exists(os.path.join(path, '__init__.py')): + break + + if sys.path[0] != path: + sys.path.insert(0, path) + + return '.'.join(module_name[::-1]) + + +def locate_app(script_info, module_name, app_name, raise_if_not_found=True): + __traceback_hide__ = True + + try: + __import__(module_name) + except ImportError: + # Reraise the ImportError if it occurred within the imported module. + # Determine this by checking whether the trace has a depth > 1. + if sys.exc_info()[-1].tb_next: + raise NoAppException( + 'While importing "{name}", an ImportError was raised:' + '\n\n{tb}'.format(name=module_name, tb=traceback.format_exc()) + ) + elif raise_if_not_found: + raise NoAppException( + 'Could not import "{name}".'.format(name=module_name) + ) + else: + return + + module = sys.modules[module_name] + + if app_name is None: + return find_best_app(script_info, module) + else: + return find_app_by_string(script_info, module, app_name) + + +def get_version(ctx, param, value): + if not value or ctx.resilient_parsing: + return + message = 'Flask %(version)s\nPython %(python_version)s' + click.echo(message % { + 'version': __version__, + 'python_version': sys.version, + }, color=ctx.color) + ctx.exit() + + +version_option = click.Option( + ['--version'], + help='Show the flask version', + expose_value=False, + callback=get_version, + is_flag=True, + is_eager=True +) + + +class DispatchingApp(object): + """Special application that dispatches to a Flask application which + is imported by name in a background thread. If an error happens + it is recorded and shown as part of the WSGI handling which in case + of the Werkzeug debugger means that it shows up in the browser. + """ + + def __init__(self, loader, use_eager_loading=False): + self.loader = loader + self._app = None + self._lock = Lock() + self._bg_loading_exc_info = None + if use_eager_loading: + self._load_unlocked() + else: + self._load_in_background() + + def _load_in_background(self): + def _load_app(): + __traceback_hide__ = True + with self._lock: + try: + self._load_unlocked() + except Exception: + self._bg_loading_exc_info = sys.exc_info() + t = Thread(target=_load_app, args=()) + t.start() + + def _flush_bg_loading_exception(self): + __traceback_hide__ = True + exc_info = self._bg_loading_exc_info + if exc_info is not None: + self._bg_loading_exc_info = None + reraise(*exc_info) + + def _load_unlocked(self): + __traceback_hide__ = True + self._app = rv = self.loader() + self._bg_loading_exc_info = None + return rv + + def __call__(self, environ, start_response): + __traceback_hide__ = True + if self._app is not None: + return self._app(environ, start_response) + self._flush_bg_loading_exception() + with self._lock: + if self._app is not None: + rv = self._app + else: + rv = self._load_unlocked() + return rv(environ, start_response) + + +class ScriptInfo(object): + """Help object to deal with Flask applications. This is usually not + necessary to interface with as it's used internally in the dispatching + to click. In future versions of Flask this object will most likely play + a bigger role. Typically it's created automatically by the + :class:`FlaskGroup` but you can also manually create it and pass it + onwards as click object. + """ + + def __init__(self, app_import_path=None, create_app=None): + #: Optionally the import path for the Flask application. + self.app_import_path = app_import_path or os.environ.get('FLASK_APP') + #: Optionally a function that is passed the script info to create + #: the instance of the application. + self.create_app = create_app + #: A dictionary with arbitrary data that can be associated with + #: this script info. + self.data = {} + self._loaded_app = None + + def load_app(self): + """Loads the Flask app (if not yet loaded) and returns it. Calling + this multiple times will just result in the already loaded app to + be returned. + """ + __traceback_hide__ = True + + if self._loaded_app is not None: + return self._loaded_app + + app = None + + if self.create_app is not None: + app = call_factory(self, self.create_app) + else: + if self.app_import_path: + path, name = (self.app_import_path.split(':', 1) + [None])[:2] + import_name = prepare_import(path) + app = locate_app(self, import_name, name) + else: + for path in ('wsgi.py', 'app.py'): + import_name = prepare_import(path) + app = locate_app(self, import_name, None, + raise_if_not_found=False) + + if app: + break + + if not app: + raise NoAppException( + 'Could not locate a Flask application. You did not provide ' + 'the "FLASK_APP" environment variable, and a "wsgi.py" or ' + '"app.py" module was not found in the current directory.' + ) + + debug = get_debug_flag() + + # Update the app's debug flag through the descriptor so that other + # values repopulate as well. + if debug is not None: + app.debug = debug + + self._loaded_app = app + return app + + +pass_script_info = click.make_pass_decorator(ScriptInfo, ensure=True) + + +def with_appcontext(f): + """Wraps a callback so that it's guaranteed to be executed with the + script's application context. If callbacks are registered directly + to the ``app.cli`` object then they are wrapped with this function + by default unless it's disabled. + """ + @click.pass_context + def decorator(__ctx, *args, **kwargs): + with __ctx.ensure_object(ScriptInfo).load_app().app_context(): + return __ctx.invoke(f, *args, **kwargs) + return update_wrapper(decorator, f) + + +class AppGroup(click.Group): + """This works similar to a regular click :class:`~click.Group` but it + changes the behavior of the :meth:`command` decorator so that it + automatically wraps the functions in :func:`with_appcontext`. + + Not to be confused with :class:`FlaskGroup`. + """ + + def command(self, *args, **kwargs): + """This works exactly like the method of the same name on a regular + :class:`click.Group` but it wraps callbacks in :func:`with_appcontext` + unless it's disabled by passing ``with_appcontext=False``. + """ + wrap_for_ctx = kwargs.pop('with_appcontext', True) + def decorator(f): + if wrap_for_ctx: + f = with_appcontext(f) + return click.Group.command(self, *args, **kwargs)(f) + return decorator + + def group(self, *args, **kwargs): + """This works exactly like the method of the same name on a regular + :class:`click.Group` but it defaults the group class to + :class:`AppGroup`. + """ + kwargs.setdefault('cls', AppGroup) + return click.Group.group(self, *args, **kwargs) + + +class FlaskGroup(AppGroup): + """Special subclass of the :class:`AppGroup` group that supports + loading more commands from the configured Flask app. Normally a + developer does not have to interface with this class but there are + some very advanced use cases for which it makes sense to create an + instance of this. + + For information as of why this is useful see :ref:`custom-scripts`. + + :param add_default_commands: if this is True then the default run and + shell commands wil be added. + :param add_version_option: adds the ``--version`` option. + :param create_app: an optional callback that is passed the script info and + returns the loaded app. + :param load_dotenv: Load the nearest :file:`.env` and :file:`.flaskenv` + files to set environment variables. Will also change the working + directory to the directory containing the first file found. + + .. versionchanged:: 1.0 + If installed, python-dotenv will be used to load environment variables + from :file:`.env` and :file:`.flaskenv` files. + """ + + def __init__(self, add_default_commands=True, create_app=None, + add_version_option=True, load_dotenv=True, **extra): + params = list(extra.pop('params', None) or ()) + + if add_version_option: + params.append(version_option) + + AppGroup.__init__(self, params=params, **extra) + self.create_app = create_app + self.load_dotenv = load_dotenv + + if add_default_commands: + self.add_command(run_command) + self.add_command(shell_command) + self.add_command(routes_command) + + self._loaded_plugin_commands = False + + def _load_plugin_commands(self): + if self._loaded_plugin_commands: + return + try: + import pkg_resources + except ImportError: + self._loaded_plugin_commands = True + return + + for ep in pkg_resources.iter_entry_points('flask.commands'): + self.add_command(ep.load(), ep.name) + self._loaded_plugin_commands = True + + def get_command(self, ctx, name): + self._load_plugin_commands() + + # We load built-in commands first as these should always be the + # same no matter what the app does. If the app does want to + # override this it needs to make a custom instance of this group + # and not attach the default commands. + # + # This also means that the script stays functional in case the + # application completely fails. + rv = AppGroup.get_command(self, ctx, name) + if rv is not None: + return rv + + info = ctx.ensure_object(ScriptInfo) + try: + rv = info.load_app().cli.get_command(ctx, name) + if rv is not None: + return rv + except NoAppException: + pass + + def list_commands(self, ctx): + self._load_plugin_commands() + + # The commands available is the list of both the application (if + # available) plus the builtin commands. + rv = set(click.Group.list_commands(self, ctx)) + info = ctx.ensure_object(ScriptInfo) + try: + rv.update(info.load_app().cli.list_commands(ctx)) + except Exception: + # Here we intentionally swallow all exceptions as we don't + # want the help page to break if the app does not exist. + # If someone attempts to use the command we try to create + # the app again and this will give us the error. + # However, we will not do so silently because that would confuse + # users. + traceback.print_exc() + return sorted(rv) + + def main(self, *args, **kwargs): + # Set a global flag that indicates that we were invoked from the + # command line interface. This is detected by Flask.run to make the + # call into a no-op. This is necessary to avoid ugly errors when the + # script that is loaded here also attempts to start a server. + os.environ['FLASK_RUN_FROM_CLI'] = 'true' + + if get_load_dotenv(self.load_dotenv): + load_dotenv() + + obj = kwargs.get('obj') + + if obj is None: + obj = ScriptInfo(create_app=self.create_app) + + kwargs['obj'] = obj + kwargs.setdefault('auto_envvar_prefix', 'FLASK') + return super(FlaskGroup, self).main(*args, **kwargs) + + +def _path_is_ancestor(path, other): + """Take ``other`` and remove the length of ``path`` from it. Then join it + to ``path``. If it is the original value, ``path`` is an ancestor of + ``other``.""" + return os.path.join(path, other[len(path):].lstrip(os.sep)) == other + + +def load_dotenv(path=None): + """Load "dotenv" files in order of precedence to set environment variables. + + If an env var is already set it is not overwritten, so earlier files in the + list are preferred over later files. + + Changes the current working directory to the location of the first file + found, with the assumption that it is in the top level project directory + and will be where the Python path should import local packages from. + + This is a no-op if `python-dotenv`_ is not installed. + + .. _python-dotenv: https://github.com/theskumar/python-dotenv#readme + + :param path: Load the file at this location instead of searching. + :return: ``True`` if a file was loaded. + + .. versionadded:: 1.0 + """ + if dotenv is None: + if path or os.path.exists('.env') or os.path.exists('.flaskenv'): + click.secho( + ' * Tip: There are .env files present.' + ' Do "pip install python-dotenv" to use them.', + fg='yellow') + return + + if path is not None: + return dotenv.load_dotenv(path) + + new_dir = None + + for name in ('.env', '.flaskenv'): + path = dotenv.find_dotenv(name, usecwd=True) + + if not path: + continue + + if new_dir is None: + new_dir = os.path.dirname(path) + + dotenv.load_dotenv(path) + + if new_dir and os.getcwd() != new_dir: + os.chdir(new_dir) + + return new_dir is not None # at least one file was located and loaded + + +def show_server_banner(env, debug, app_import_path, eager_loading): + """Show extra startup messages the first time the server is run, + ignoring the reloader. + """ + if os.environ.get('WERKZEUG_RUN_MAIN') == 'true': + return + + if app_import_path is not None: + message = ' * Serving Flask app "{0}"'.format(app_import_path) + + if not eager_loading: + message += ' (lazy loading)' + + click.echo(message) + + click.echo(' * Environment: {0}'.format(env)) + + if env == 'production': + click.secho( + ' WARNING: Do not use the development server in a production' + ' environment.', fg='red') + click.secho(' Use a production WSGI server instead.', dim=True) + + if debug is not None: + click.echo(' * Debug mode: {0}'.format('on' if debug else 'off')) + + +class CertParamType(click.ParamType): + """Click option type for the ``--cert`` option. Allows either an + existing file, the string ``'adhoc'``, or an import for a + :class:`~ssl.SSLContext` object. + """ + + name = 'path' + + def __init__(self): + self.path_type = click.Path( + exists=True, dir_okay=False, resolve_path=True) + + def convert(self, value, param, ctx): + try: + return self.path_type(value, param, ctx) + except click.BadParameter: + value = click.STRING(value, param, ctx).lower() + + if value == 'adhoc': + try: + import OpenSSL + except ImportError: + raise click.BadParameter( + 'Using ad-hoc certificates requires pyOpenSSL.', + ctx, param) + + return value + + obj = import_string(value, silent=True) + + if sys.version_info < (2, 7): + if obj: + return obj + else: + if isinstance(obj, ssl.SSLContext): + return obj + + raise + + +def _validate_key(ctx, param, value): + """The ``--key`` option must be specified when ``--cert`` is a file. + Modifies the ``cert`` param to be a ``(cert, key)`` pair if needed. + """ + cert = ctx.params.get('cert') + is_adhoc = cert == 'adhoc' + + if sys.version_info < (2, 7): + is_context = cert and not isinstance(cert, (text_type, bytes)) + else: + is_context = isinstance(cert, ssl.SSLContext) + + if value is not None: + if is_adhoc: + raise click.BadParameter( + 'When "--cert" is "adhoc", "--key" is not used.', + ctx, param) + + if is_context: + raise click.BadParameter( + 'When "--cert" is an SSLContext object, "--key is not used.', + ctx, param) + + if not cert: + raise click.BadParameter( + '"--cert" must also be specified.', + ctx, param) + + ctx.params['cert'] = cert, value + + else: + if cert and not (is_adhoc or is_context): + raise click.BadParameter( + 'Required when using "--cert".', + ctx, param) + + return value + + +@click.command('run', short_help='Runs a development server.') +@click.option('--host', '-h', default='127.0.0.1', + help='The interface to bind to.') +@click.option('--port', '-p', default=5000, + help='The port to bind to.') +@click.option('--cert', type=CertParamType(), + help='Specify a certificate file to use HTTPS.') +@click.option('--key', + type=click.Path(exists=True, dir_okay=False, resolve_path=True), + callback=_validate_key, expose_value=False, + help='The key file to use when specifying a certificate.') +@click.option('--reload/--no-reload', default=None, + help='Enable or disable the reloader. By default the reloader ' + 'is active if debug is enabled.') +@click.option('--debugger/--no-debugger', default=None, + help='Enable or disable the debugger. By default the debugger ' + 'is active if debug is enabled.') +@click.option('--eager-loading/--lazy-loader', default=None, + help='Enable or disable eager loading. By default eager ' + 'loading is enabled if the reloader is disabled.') +@click.option('--with-threads/--without-threads', default=True, + help='Enable or disable multithreading.') +@pass_script_info +def run_command(info, host, port, reload, debugger, eager_loading, + with_threads, cert): + """Run a local development server. + + This server is for development purposes only. It does not provide + the stability, security, or performance of production WSGI servers. + + The reloader and debugger are enabled by default if + FLASK_ENV=development or FLASK_DEBUG=1. + """ + debug = get_debug_flag() + + if reload is None: + reload = debug + + if debugger is None: + debugger = debug + + if eager_loading is None: + eager_loading = not reload + + show_server_banner(get_env(), debug, info.app_import_path, eager_loading) + app = DispatchingApp(info.load_app, use_eager_loading=eager_loading) + + from werkzeug.serving import run_simple + run_simple(host, port, app, use_reloader=reload, use_debugger=debugger, + threaded=with_threads, ssl_context=cert) + + +@click.command('shell', short_help='Runs a shell in the app context.') +@with_appcontext +def shell_command(): + """Runs an interactive Python shell in the context of a given + Flask application. The application will populate the default + namespace of this shell according to it's configuration. + + This is useful for executing small snippets of management code + without having to manually configure the application. + """ + import code + from flask.globals import _app_ctx_stack + app = _app_ctx_stack.top.app + banner = 'Python %s on %s\nApp: %s [%s]\nInstance: %s' % ( + sys.version, + sys.platform, + app.import_name, + app.env, + app.instance_path, + ) + ctx = {} + + # Support the regular Python interpreter startup script if someone + # is using it. + startup = os.environ.get('PYTHONSTARTUP') + if startup and os.path.isfile(startup): + with open(startup, 'r') as f: + eval(compile(f.read(), startup, 'exec'), ctx) + + ctx.update(app.make_shell_context()) + + code.interact(banner=banner, local=ctx) + + +@click.command('routes', short_help='Show the routes for the app.') +@click.option( + '--sort', '-s', + type=click.Choice(('endpoint', 'methods', 'rule', 'match')), + default='endpoint', + help=( + 'Method to sort routes by. "match" is the order that Flask will match ' + 'routes when dispatching a request.' + ) +) +@click.option( + '--all-methods', + is_flag=True, + help="Show HEAD and OPTIONS methods." +) +@with_appcontext +def routes_command(sort, all_methods): + """Show all registered routes with endpoints and methods.""" + + rules = list(current_app.url_map.iter_rules()) + if not rules: + click.echo('No routes were registered.') + return + + ignored_methods = set(() if all_methods else ('HEAD', 'OPTIONS')) + + if sort in ('endpoint', 'rule'): + rules = sorted(rules, key=attrgetter(sort)) + elif sort == 'methods': + rules = sorted(rules, key=lambda rule: sorted(rule.methods)) + + rule_methods = [ + ', '.join(sorted(rule.methods - ignored_methods)) for rule in rules + ] + + headers = ('Endpoint', 'Methods', 'Rule') + widths = ( + max(len(rule.endpoint) for rule in rules), + max(len(methods) for methods in rule_methods), + max(len(rule.rule) for rule in rules), + ) + widths = [max(len(h), w) for h, w in zip(headers, widths)] + row = '{{0:<{0}}} {{1:<{1}}} {{2:<{2}}}'.format(*widths) + + click.echo(row.format(*headers).strip()) + click.echo(row.format(*('-' * width for width in widths))) + + for rule, methods in zip(rules, rule_methods): + click.echo(row.format(rule.endpoint, methods, rule.rule).rstrip()) + + +cli = FlaskGroup(help="""\ +A general utility script for Flask applications. + +Provides commands from Flask, extensions, and the application. Loads the +application defined in the FLASK_APP environment variable, or from a wsgi.py +file. Setting the FLASK_ENV environment variable to 'development' will enable +debug mode. + +\b + {prefix}{cmd} FLASK_APP=hello.py + {prefix}{cmd} FLASK_ENV=development + {prefix}flask run +""".format( + cmd='export' if os.name == 'posix' else 'set', + prefix='$ ' if os.name == 'posix' else '> ' +)) + + +def main(as_module=False): + args = sys.argv[1:] + + if as_module: + this_module = 'flask' + + if sys.version_info < (2, 7): + this_module += '.cli' + + name = 'python -m ' + this_module + + # Python rewrites "python -m flask" to the path to the file in argv. + # Restore the original command so that the reloader works. + sys.argv = ['-m', this_module] + args + else: + name = None + + cli.main(args=args, prog_name=name) + + +if __name__ == '__main__': + main(as_module=True) diff --git a/pyextra/flask/config.py b/pyextra/flask/config.py new file mode 100644 index 00000000000000..d6074baa8565e4 --- /dev/null +++ b/pyextra/flask/config.py @@ -0,0 +1,265 @@ +# -*- coding: utf-8 -*- +""" + flask.config + ~~~~~~~~~~~~ + + Implements the configuration related objects. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +import types +import errno + +from werkzeug.utils import import_string +from ._compat import string_types, iteritems +from . import json + + +class ConfigAttribute(object): + """Makes an attribute forward to the config""" + + def __init__(self, name, get_converter=None): + self.__name__ = name + self.get_converter = get_converter + + def __get__(self, obj, type=None): + if obj is None: + return self + rv = obj.config[self.__name__] + if self.get_converter is not None: + rv = self.get_converter(rv) + return rv + + def __set__(self, obj, value): + obj.config[self.__name__] = value + + +class Config(dict): + """Works exactly like a dict but provides ways to fill it from files + or special dictionaries. There are two common patterns to populate the + config. + + Either you can fill the config from a config file:: + + app.config.from_pyfile('yourconfig.cfg') + + Or alternatively you can define the configuration options in the + module that calls :meth:`from_object` or provide an import path to + a module that should be loaded. It is also possible to tell it to + use the same module and with that provide the configuration values + just before the call:: + + DEBUG = True + SECRET_KEY = 'development key' + app.config.from_object(__name__) + + In both cases (loading from any Python file or loading from modules), + only uppercase keys are added to the config. This makes it possible to use + lowercase values in the config file for temporary values that are not added + to the config or to define the config keys in the same file that implements + the application. + + Probably the most interesting way to load configurations is from an + environment variable pointing to a file:: + + app.config.from_envvar('YOURAPPLICATION_SETTINGS') + + In this case before launching the application you have to set this + environment variable to the file you want to use. On Linux and OS X + use the export statement:: + + export YOURAPPLICATION_SETTINGS='/path/to/config/file' + + On windows use `set` instead. + + :param root_path: path to which files are read relative from. When the + config object is created by the application, this is + the application's :attr:`~flask.Flask.root_path`. + :param defaults: an optional dictionary of default values + """ + + def __init__(self, root_path, defaults=None): + dict.__init__(self, defaults or {}) + self.root_path = root_path + + def from_envvar(self, variable_name, silent=False): + """Loads a configuration from an environment variable pointing to + a configuration file. This is basically just a shortcut with nicer + error messages for this line of code:: + + app.config.from_pyfile(os.environ['YOURAPPLICATION_SETTINGS']) + + :param variable_name: name of the environment variable + :param silent: set to ``True`` if you want silent failure for missing + files. + :return: bool. ``True`` if able to load config, ``False`` otherwise. + """ + rv = os.environ.get(variable_name) + if not rv: + if silent: + return False + raise RuntimeError('The environment variable %r is not set ' + 'and as such configuration could not be ' + 'loaded. Set this variable and make it ' + 'point to a configuration file' % + variable_name) + return self.from_pyfile(rv, silent=silent) + + def from_pyfile(self, filename, silent=False): + """Updates the values in the config from a Python file. This function + behaves as if the file was imported as module with the + :meth:`from_object` function. + + :param filename: the filename of the config. This can either be an + absolute filename or a filename relative to the + root path. + :param silent: set to ``True`` if you want silent failure for missing + files. + + .. versionadded:: 0.7 + `silent` parameter. + """ + filename = os.path.join(self.root_path, filename) + d = types.ModuleType('config') + d.__file__ = filename + try: + with open(filename, mode='rb') as config_file: + exec(compile(config_file.read(), filename, 'exec'), d.__dict__) + except IOError as e: + if silent and e.errno in ( + errno.ENOENT, errno.EISDIR, errno.ENOTDIR + ): + return False + e.strerror = 'Unable to load configuration file (%s)' % e.strerror + raise + self.from_object(d) + return True + + def from_object(self, obj): + """Updates the values from the given object. An object can be of one + of the following two types: + + - a string: in this case the object with that name will be imported + - an actual object reference: that object is used directly + + Objects are usually either modules or classes. :meth:`from_object` + loads only the uppercase attributes of the module/class. A ``dict`` + object will not work with :meth:`from_object` because the keys of a + ``dict`` are not attributes of the ``dict`` class. + + Example of module-based configuration:: + + app.config.from_object('yourapplication.default_config') + from yourapplication import default_config + app.config.from_object(default_config) + + You should not use this function to load the actual configuration but + rather configuration defaults. The actual config should be loaded + with :meth:`from_pyfile` and ideally from a location not within the + package because the package might be installed system wide. + + See :ref:`config-dev-prod` for an example of class-based configuration + using :meth:`from_object`. + + :param obj: an import name or object + """ + if isinstance(obj, string_types): + obj = import_string(obj) + for key in dir(obj): + if key.isupper(): + self[key] = getattr(obj, key) + + def from_json(self, filename, silent=False): + """Updates the values in the config from a JSON file. This function + behaves as if the JSON object was a dictionary and passed to the + :meth:`from_mapping` function. + + :param filename: the filename of the JSON file. This can either be an + absolute filename or a filename relative to the + root path. + :param silent: set to ``True`` if you want silent failure for missing + files. + + .. versionadded:: 0.11 + """ + filename = os.path.join(self.root_path, filename) + + try: + with open(filename) as json_file: + obj = json.loads(json_file.read()) + except IOError as e: + if silent and e.errno in (errno.ENOENT, errno.EISDIR): + return False + e.strerror = 'Unable to load configuration file (%s)' % e.strerror + raise + return self.from_mapping(obj) + + def from_mapping(self, *mapping, **kwargs): + """Updates the config like :meth:`update` ignoring items with non-upper + keys. + + .. versionadded:: 0.11 + """ + mappings = [] + if len(mapping) == 1: + if hasattr(mapping[0], 'items'): + mappings.append(mapping[0].items()) + else: + mappings.append(mapping[0]) + elif len(mapping) > 1: + raise TypeError( + 'expected at most 1 positional argument, got %d' % len(mapping) + ) + mappings.append(kwargs.items()) + for mapping in mappings: + for (key, value) in mapping: + if key.isupper(): + self[key] = value + return True + + def get_namespace(self, namespace, lowercase=True, trim_namespace=True): + """Returns a dictionary containing a subset of configuration options + that match the specified namespace/prefix. Example usage:: + + app.config['IMAGE_STORE_TYPE'] = 'fs' + app.config['IMAGE_STORE_PATH'] = '/var/app/images' + app.config['IMAGE_STORE_BASE_URL'] = 'http://img.website.com' + image_store_config = app.config.get_namespace('IMAGE_STORE_') + + The resulting dictionary `image_store_config` would look like:: + + { + 'type': 'fs', + 'path': '/var/app/images', + 'base_url': 'http://img.website.com' + } + + This is often useful when configuration options map directly to + keyword arguments in functions or class constructors. + + :param namespace: a configuration namespace + :param lowercase: a flag indicating if the keys of the resulting + dictionary should be lowercase + :param trim_namespace: a flag indicating if the keys of the resulting + dictionary should not include the namespace + + .. versionadded:: 0.11 + """ + rv = {} + for k, v in iteritems(self): + if not k.startswith(namespace): + continue + if trim_namespace: + key = k[len(namespace):] + else: + key = k + if lowercase: + key = key.lower() + rv[key] = v + return rv + + def __repr__(self): + return '<%s %s>' % (self.__class__.__name__, dict.__repr__(self)) diff --git a/pyextra/flask/ctx.py b/pyextra/flask/ctx.py new file mode 100644 index 00000000000000..8472c920c2d6ef --- /dev/null +++ b/pyextra/flask/ctx.py @@ -0,0 +1,457 @@ +# -*- coding: utf-8 -*- +""" + flask.ctx + ~~~~~~~~~ + + Implements the objects required to keep the context. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import sys +from functools import update_wrapper + +from werkzeug.exceptions import HTTPException + +from .globals import _request_ctx_stack, _app_ctx_stack +from .signals import appcontext_pushed, appcontext_popped +from ._compat import BROKEN_PYPY_CTXMGR_EXIT, reraise + + +# a singleton sentinel value for parameter defaults +_sentinel = object() + + +class _AppCtxGlobals(object): + """A plain object. Used as a namespace for storing data during an + application context. + + Creating an app context automatically creates this object, which is + made available as the :data:`g` proxy. + + .. describe:: 'key' in g + + Check whether an attribute is present. + + .. versionadded:: 0.10 + + .. describe:: iter(g) + + Return an iterator over the attribute names. + + .. versionadded:: 0.10 + """ + + def get(self, name, default=None): + """Get an attribute by name, or a default value. Like + :meth:`dict.get`. + + :param name: Name of attribute to get. + :param default: Value to return if the attribute is not present. + + .. versionadded:: 0.10 + """ + return self.__dict__.get(name, default) + + def pop(self, name, default=_sentinel): + """Get and remove an attribute by name. Like :meth:`dict.pop`. + + :param name: Name of attribute to pop. + :param default: Value to return if the attribute is not present, + instead of raise a ``KeyError``. + + .. versionadded:: 0.11 + """ + if default is _sentinel: + return self.__dict__.pop(name) + else: + return self.__dict__.pop(name, default) + + def setdefault(self, name, default=None): + """Get the value of an attribute if it is present, otherwise + set and return a default value. Like :meth:`dict.setdefault`. + + :param name: Name of attribute to get. + :param: default: Value to set and return if the attribute is not + present. + + .. versionadded:: 0.11 + """ + return self.__dict__.setdefault(name, default) + + def __contains__(self, item): + return item in self.__dict__ + + def __iter__(self): + return iter(self.__dict__) + + def __repr__(self): + top = _app_ctx_stack.top + if top is not None: + return '' % top.app.name + return object.__repr__(self) + + +def after_this_request(f): + """Executes a function after this request. This is useful to modify + response objects. The function is passed the response object and has + to return the same or a new one. + + Example:: + + @app.route('/') + def index(): + @after_this_request + def add_header(response): + response.headers['X-Foo'] = 'Parachute' + return response + return 'Hello World!' + + This is more useful if a function other than the view function wants to + modify a response. For instance think of a decorator that wants to add + some headers without converting the return value into a response object. + + .. versionadded:: 0.9 + """ + _request_ctx_stack.top._after_request_functions.append(f) + return f + + +def copy_current_request_context(f): + """A helper function that decorates a function to retain the current + request context. This is useful when working with greenlets. The moment + the function is decorated a copy of the request context is created and + then pushed when the function is called. + + Example:: + + import gevent + from flask import copy_current_request_context + + @app.route('/') + def index(): + @copy_current_request_context + def do_some_work(): + # do some work here, it can access flask.request like you + # would otherwise in the view function. + ... + gevent.spawn(do_some_work) + return 'Regular response' + + .. versionadded:: 0.10 + """ + top = _request_ctx_stack.top + if top is None: + raise RuntimeError('This decorator can only be used at local scopes ' + 'when a request context is on the stack. For instance within ' + 'view functions.') + reqctx = top.copy() + def wrapper(*args, **kwargs): + with reqctx: + return f(*args, **kwargs) + return update_wrapper(wrapper, f) + + +def has_request_context(): + """If you have code that wants to test if a request context is there or + not this function can be used. For instance, you may want to take advantage + of request information if the request object is available, but fail + silently if it is unavailable. + + :: + + class User(db.Model): + + def __init__(self, username, remote_addr=None): + self.username = username + if remote_addr is None and has_request_context(): + remote_addr = request.remote_addr + self.remote_addr = remote_addr + + Alternatively you can also just test any of the context bound objects + (such as :class:`request` or :class:`g` for truthness):: + + class User(db.Model): + + def __init__(self, username, remote_addr=None): + self.username = username + if remote_addr is None and request: + remote_addr = request.remote_addr + self.remote_addr = remote_addr + + .. versionadded:: 0.7 + """ + return _request_ctx_stack.top is not None + + +def has_app_context(): + """Works like :func:`has_request_context` but for the application + context. You can also just do a boolean check on the + :data:`current_app` object instead. + + .. versionadded:: 0.9 + """ + return _app_ctx_stack.top is not None + + +class AppContext(object): + """The application context binds an application object implicitly + to the current thread or greenlet, similar to how the + :class:`RequestContext` binds request information. The application + context is also implicitly created if a request context is created + but the application is not on top of the individual application + context. + """ + + def __init__(self, app): + self.app = app + self.url_adapter = app.create_url_adapter(None) + self.g = app.app_ctx_globals_class() + + # Like request context, app contexts can be pushed multiple times + # but there a basic "refcount" is enough to track them. + self._refcnt = 0 + + def push(self): + """Binds the app context to the current context.""" + self._refcnt += 1 + if hasattr(sys, 'exc_clear'): + sys.exc_clear() + _app_ctx_stack.push(self) + appcontext_pushed.send(self.app) + + def pop(self, exc=_sentinel): + """Pops the app context.""" + try: + self._refcnt -= 1 + if self._refcnt <= 0: + if exc is _sentinel: + exc = sys.exc_info()[1] + self.app.do_teardown_appcontext(exc) + finally: + rv = _app_ctx_stack.pop() + assert rv is self, 'Popped wrong app context. (%r instead of %r)' \ + % (rv, self) + appcontext_popped.send(self.app) + + def __enter__(self): + self.push() + return self + + def __exit__(self, exc_type, exc_value, tb): + self.pop(exc_value) + + if BROKEN_PYPY_CTXMGR_EXIT and exc_type is not None: + reraise(exc_type, exc_value, tb) + + +class RequestContext(object): + """The request context contains all request relevant information. It is + created at the beginning of the request and pushed to the + `_request_ctx_stack` and removed at the end of it. It will create the + URL adapter and request object for the WSGI environment provided. + + Do not attempt to use this class directly, instead use + :meth:`~flask.Flask.test_request_context` and + :meth:`~flask.Flask.request_context` to create this object. + + When the request context is popped, it will evaluate all the + functions registered on the application for teardown execution + (:meth:`~flask.Flask.teardown_request`). + + The request context is automatically popped at the end of the request + for you. In debug mode the request context is kept around if + exceptions happen so that interactive debuggers have a chance to + introspect the data. With 0.4 this can also be forced for requests + that did not fail and outside of ``DEBUG`` mode. By setting + ``'flask._preserve_context'`` to ``True`` on the WSGI environment the + context will not pop itself at the end of the request. This is used by + the :meth:`~flask.Flask.test_client` for example to implement the + deferred cleanup functionality. + + You might find this helpful for unittests where you need the + information from the context local around for a little longer. Make + sure to properly :meth:`~werkzeug.LocalStack.pop` the stack yourself in + that situation, otherwise your unittests will leak memory. + """ + + def __init__(self, app, environ, request=None): + self.app = app + if request is None: + request = app.request_class(environ) + self.request = request + self.url_adapter = app.create_url_adapter(self.request) + self.flashes = None + self.session = None + + # Request contexts can be pushed multiple times and interleaved with + # other request contexts. Now only if the last level is popped we + # get rid of them. Additionally if an application context is missing + # one is created implicitly so for each level we add this information + self._implicit_app_ctx_stack = [] + + # indicator if the context was preserved. Next time another context + # is pushed the preserved context is popped. + self.preserved = False + + # remembers the exception for pop if there is one in case the context + # preservation kicks in. + self._preserved_exc = None + + # Functions that should be executed after the request on the response + # object. These will be called before the regular "after_request" + # functions. + self._after_request_functions = [] + + self.match_request() + + def _get_g(self): + return _app_ctx_stack.top.g + def _set_g(self, value): + _app_ctx_stack.top.g = value + g = property(_get_g, _set_g) + del _get_g, _set_g + + def copy(self): + """Creates a copy of this request context with the same request object. + This can be used to move a request context to a different greenlet. + Because the actual request object is the same this cannot be used to + move a request context to a different thread unless access to the + request object is locked. + + .. versionadded:: 0.10 + """ + return self.__class__(self.app, + environ=self.request.environ, + request=self.request + ) + + def match_request(self): + """Can be overridden by a subclass to hook into the matching + of the request. + """ + try: + url_rule, self.request.view_args = \ + self.url_adapter.match(return_rule=True) + self.request.url_rule = url_rule + except HTTPException as e: + self.request.routing_exception = e + + def push(self): + """Binds the request context to the current context.""" + # If an exception occurs in debug mode or if context preservation is + # activated under exception situations exactly one context stays + # on the stack. The rationale is that you want to access that + # information under debug situations. However if someone forgets to + # pop that context again we want to make sure that on the next push + # it's invalidated, otherwise we run at risk that something leaks + # memory. This is usually only a problem in test suite since this + # functionality is not active in production environments. + top = _request_ctx_stack.top + if top is not None and top.preserved: + top.pop(top._preserved_exc) + + # Before we push the request context we have to ensure that there + # is an application context. + app_ctx = _app_ctx_stack.top + if app_ctx is None or app_ctx.app != self.app: + app_ctx = self.app.app_context() + app_ctx.push() + self._implicit_app_ctx_stack.append(app_ctx) + else: + self._implicit_app_ctx_stack.append(None) + + if hasattr(sys, 'exc_clear'): + sys.exc_clear() + + _request_ctx_stack.push(self) + + # Open the session at the moment that the request context is available. + # This allows a custom open_session method to use the request context. + # Only open a new session if this is the first time the request was + # pushed, otherwise stream_with_context loses the session. + if self.session is None: + session_interface = self.app.session_interface + self.session = session_interface.open_session( + self.app, self.request + ) + + if self.session is None: + self.session = session_interface.make_null_session(self.app) + + def pop(self, exc=_sentinel): + """Pops the request context and unbinds it by doing that. This will + also trigger the execution of functions registered by the + :meth:`~flask.Flask.teardown_request` decorator. + + .. versionchanged:: 0.9 + Added the `exc` argument. + """ + app_ctx = self._implicit_app_ctx_stack.pop() + + try: + clear_request = False + if not self._implicit_app_ctx_stack: + self.preserved = False + self._preserved_exc = None + if exc is _sentinel: + exc = sys.exc_info()[1] + self.app.do_teardown_request(exc) + + # If this interpreter supports clearing the exception information + # we do that now. This will only go into effect on Python 2.x, + # on 3.x it disappears automatically at the end of the exception + # stack. + if hasattr(sys, 'exc_clear'): + sys.exc_clear() + + request_close = getattr(self.request, 'close', None) + if request_close is not None: + request_close() + clear_request = True + finally: + rv = _request_ctx_stack.pop() + + # get rid of circular dependencies at the end of the request + # so that we don't require the GC to be active. + if clear_request: + rv.request.environ['werkzeug.request'] = None + + # Get rid of the app as well if necessary. + if app_ctx is not None: + app_ctx.pop(exc) + + assert rv is self, 'Popped wrong request context. ' \ + '(%r instead of %r)' % (rv, self) + + def auto_pop(self, exc): + if self.request.environ.get('flask._preserve_context') or \ + (exc is not None and self.app.preserve_context_on_exception): + self.preserved = True + self._preserved_exc = exc + else: + self.pop(exc) + + def __enter__(self): + self.push() + return self + + def __exit__(self, exc_type, exc_value, tb): + # do not pop the request stack if we are in debug mode and an + # exception happened. This will allow the debugger to still + # access the request object in the interactive shell. Furthermore + # the context can be force kept alive for the test client. + # See flask.testing for how this works. + self.auto_pop(exc_value) + + if BROKEN_PYPY_CTXMGR_EXIT and exc_type is not None: + reraise(exc_type, exc_value, tb) + + def __repr__(self): + return '<%s \'%s\' [%s] of %s>' % ( + self.__class__.__name__, + self.request.url, + self.request.method, + self.app.name, + ) diff --git a/pyextra/flask/debughelpers.py b/pyextra/flask/debughelpers.py new file mode 100644 index 00000000000000..e9765f20d0a2e4 --- /dev/null +++ b/pyextra/flask/debughelpers.py @@ -0,0 +1,168 @@ +# -*- coding: utf-8 -*- +""" + flask.debughelpers + ~~~~~~~~~~~~~~~~~~ + + Various helpers to make the development experience better. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +from warnings import warn + +from ._compat import implements_to_string, text_type +from .app import Flask +from .blueprints import Blueprint +from .globals import _request_ctx_stack + + +class UnexpectedUnicodeError(AssertionError, UnicodeError): + """Raised in places where we want some better error reporting for + unexpected unicode or binary data. + """ + + +@implements_to_string +class DebugFilesKeyError(KeyError, AssertionError): + """Raised from request.files during debugging. The idea is that it can + provide a better error message than just a generic KeyError/BadRequest. + """ + + def __init__(self, request, key): + form_matches = request.form.getlist(key) + buf = ['You tried to access the file "%s" in the request.files ' + 'dictionary but it does not exist. The mimetype for the request ' + 'is "%s" instead of "multipart/form-data" which means that no ' + 'file contents were transmitted. To fix this error you should ' + 'provide enctype="multipart/form-data" in your form.' % + (key, request.mimetype)] + if form_matches: + buf.append('\n\nThe browser instead transmitted some file names. ' + 'This was submitted: %s' % ', '.join('"%s"' % x + for x in form_matches)) + self.msg = ''.join(buf) + + def __str__(self): + return self.msg + + +class FormDataRoutingRedirect(AssertionError): + """This exception is raised by Flask in debug mode if it detects a + redirect caused by the routing system when the request method is not + GET, HEAD or OPTIONS. Reasoning: form data will be dropped. + """ + + def __init__(self, request): + exc = request.routing_exception + buf = ['A request was sent to this URL (%s) but a redirect was ' + 'issued automatically by the routing system to "%s".' + % (request.url, exc.new_url)] + + # In case just a slash was appended we can be extra helpful + if request.base_url + '/' == exc.new_url.split('?')[0]: + buf.append(' The URL was defined with a trailing slash so ' + 'Flask will automatically redirect to the URL ' + 'with the trailing slash if it was accessed ' + 'without one.') + + buf.append(' Make sure to directly send your %s-request to this URL ' + 'since we can\'t make browsers or HTTP clients redirect ' + 'with form data reliably or without user interaction.' % + request.method) + buf.append('\n\nNote: this exception is only raised in debug mode') + AssertionError.__init__(self, ''.join(buf).encode('utf-8')) + + +def attach_enctype_error_multidict(request): + """Since Flask 0.8 we're monkeypatching the files object in case a + request is detected that does not use multipart form data but the files + object is accessed. + """ + oldcls = request.files.__class__ + class newcls(oldcls): + def __getitem__(self, key): + try: + return oldcls.__getitem__(self, key) + except KeyError: + if key not in request.form: + raise + raise DebugFilesKeyError(request, key) + newcls.__name__ = oldcls.__name__ + newcls.__module__ = oldcls.__module__ + request.files.__class__ = newcls + + +def _dump_loader_info(loader): + yield 'class: %s.%s' % (type(loader).__module__, type(loader).__name__) + for key, value in sorted(loader.__dict__.items()): + if key.startswith('_'): + continue + if isinstance(value, (tuple, list)): + if not all(isinstance(x, (str, text_type)) for x in value): + continue + yield '%s:' % key + for item in value: + yield ' - %s' % item + continue + elif not isinstance(value, (str, text_type, int, float, bool)): + continue + yield '%s: %r' % (key, value) + + +def explain_template_loading_attempts(app, template, attempts): + """This should help developers understand what failed""" + info = ['Locating template "%s":' % template] + total_found = 0 + blueprint = None + reqctx = _request_ctx_stack.top + if reqctx is not None and reqctx.request.blueprint is not None: + blueprint = reqctx.request.blueprint + + for idx, (loader, srcobj, triple) in enumerate(attempts): + if isinstance(srcobj, Flask): + src_info = 'application "%s"' % srcobj.import_name + elif isinstance(srcobj, Blueprint): + src_info = 'blueprint "%s" (%s)' % (srcobj.name, + srcobj.import_name) + else: + src_info = repr(srcobj) + + info.append('% 5d: trying loader of %s' % ( + idx + 1, src_info)) + + for line in _dump_loader_info(loader): + info.append(' %s' % line) + + if triple is None: + detail = 'no match' + else: + detail = 'found (%r)' % (triple[1] or '') + total_found += 1 + info.append(' -> %s' % detail) + + seems_fishy = False + if total_found == 0: + info.append('Error: the template could not be found.') + seems_fishy = True + elif total_found > 1: + info.append('Warning: multiple loaders returned a match for the template.') + seems_fishy = True + + if blueprint is not None and seems_fishy: + info.append(' The template was looked up from an endpoint that ' + 'belongs to the blueprint "%s".' % blueprint) + info.append(' Maybe you did not place a template in the right folder?') + info.append(' See http://flask.pocoo.org/docs/blueprints/#templates') + + app.logger.info('\n'.join(info)) + + +def explain_ignored_app_run(): + if os.environ.get('WERKZEUG_RUN_MAIN') != 'true': + warn(Warning('Silently ignoring app.run() because the ' + 'application is run from the flask command line ' + 'executable. Consider putting app.run() behind an ' + 'if __name__ == "__main__" guard to silence this ' + 'warning.'), stacklevel=3) diff --git a/pyextra/flask/globals.py b/pyextra/flask/globals.py new file mode 100644 index 00000000000000..7d50a6f6d4052f --- /dev/null +++ b/pyextra/flask/globals.py @@ -0,0 +1,61 @@ +# -*- coding: utf-8 -*- +""" + flask.globals + ~~~~~~~~~~~~~ + + Defines all the global objects that are proxies to the current + active context. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +from functools import partial +from werkzeug.local import LocalStack, LocalProxy + + +_request_ctx_err_msg = '''\ +Working outside of request context. + +This typically means that you attempted to use functionality that needed +an active HTTP request. Consult the documentation on testing for +information about how to avoid this problem.\ +''' +_app_ctx_err_msg = '''\ +Working outside of application context. + +This typically means that you attempted to use functionality that needed +to interface with the current application object in some way. To solve +this, set up an application context with app.app_context(). See the +documentation for more information.\ +''' + + +def _lookup_req_object(name): + top = _request_ctx_stack.top + if top is None: + raise RuntimeError(_request_ctx_err_msg) + return getattr(top, name) + + +def _lookup_app_object(name): + top = _app_ctx_stack.top + if top is None: + raise RuntimeError(_app_ctx_err_msg) + return getattr(top, name) + + +def _find_app(): + top = _app_ctx_stack.top + if top is None: + raise RuntimeError(_app_ctx_err_msg) + return top.app + + +# context locals +_request_ctx_stack = LocalStack() +_app_ctx_stack = LocalStack() +current_app = LocalProxy(_find_app) +request = LocalProxy(partial(_lookup_req_object, 'request')) +session = LocalProxy(partial(_lookup_req_object, 'session')) +g = LocalProxy(partial(_lookup_app_object, 'g')) diff --git a/pyextra/flask/helpers.py b/pyextra/flask/helpers.py new file mode 100644 index 00000000000000..df0b91fc55ee0e --- /dev/null +++ b/pyextra/flask/helpers.py @@ -0,0 +1,1044 @@ +# -*- coding: utf-8 -*- +""" + flask.helpers + ~~~~~~~~~~~~~ + + Implements various helpers. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +import socket +import sys +import pkgutil +import posixpath +import mimetypes +from time import time +from zlib import adler32 +from threading import RLock +import unicodedata +from werkzeug.routing import BuildError +from functools import update_wrapper + +from werkzeug.urls import url_quote +from werkzeug.datastructures import Headers, Range +from werkzeug.exceptions import BadRequest, NotFound, \ + RequestedRangeNotSatisfiable + +from werkzeug.wsgi import wrap_file +from jinja2 import FileSystemLoader + +from .signals import message_flashed +from .globals import session, _request_ctx_stack, _app_ctx_stack, \ + current_app, request +from ._compat import string_types, text_type, PY2 + +# sentinel +_missing = object() + + +# what separators does this operating system provide that are not a slash? +# this is used by the send_from_directory function to ensure that nobody is +# able to access files from outside the filesystem. +_os_alt_seps = list(sep for sep in [os.path.sep, os.path.altsep] + if sep not in (None, '/')) + + +def get_env(): + """Get the environment the app is running in, indicated by the + :envvar:`FLASK_ENV` environment variable. The default is + ``'production'``. + """ + return os.environ.get('FLASK_ENV') or 'production' + + +def get_debug_flag(): + """Get whether debug mode should be enabled for the app, indicated + by the :envvar:`FLASK_DEBUG` environment variable. The default is + ``True`` if :func:`.get_env` returns ``'development'``, or ``False`` + otherwise. + """ + val = os.environ.get('FLASK_DEBUG') + + if not val: + return get_env() == 'development' + + return val.lower() not in ('0', 'false', 'no') + + +def get_load_dotenv(default=True): + """Get whether the user has disabled loading dotenv files by setting + :envvar:`FLASK_SKIP_DOTENV`. The default is ``True``, load the + files. + + :param default: What to return if the env var isn't set. + """ + val = os.environ.get('FLASK_SKIP_DOTENV') + + if not val: + return default + + return val.lower() in ('0', 'false', 'no') + + +def _endpoint_from_view_func(view_func): + """Internal helper that returns the default endpoint for a given + function. This always is the function name. + """ + assert view_func is not None, 'expected view func if endpoint ' \ + 'is not provided.' + return view_func.__name__ + + +def stream_with_context(generator_or_function): + """Request contexts disappear when the response is started on the server. + This is done for efficiency reasons and to make it less likely to encounter + memory leaks with badly written WSGI middlewares. The downside is that if + you are using streamed responses, the generator cannot access request bound + information any more. + + This function however can help you keep the context around for longer:: + + from flask import stream_with_context, request, Response + + @app.route('/stream') + def streamed_response(): + @stream_with_context + def generate(): + yield 'Hello ' + yield request.args['name'] + yield '!' + return Response(generate()) + + Alternatively it can also be used around a specific generator:: + + from flask import stream_with_context, request, Response + + @app.route('/stream') + def streamed_response(): + def generate(): + yield 'Hello ' + yield request.args['name'] + yield '!' + return Response(stream_with_context(generate())) + + .. versionadded:: 0.9 + """ + try: + gen = iter(generator_or_function) + except TypeError: + def decorator(*args, **kwargs): + gen = generator_or_function(*args, **kwargs) + return stream_with_context(gen) + return update_wrapper(decorator, generator_or_function) + + def generator(): + ctx = _request_ctx_stack.top + if ctx is None: + raise RuntimeError('Attempted to stream with context but ' + 'there was no context in the first place to keep around.') + with ctx: + # Dummy sentinel. Has to be inside the context block or we're + # not actually keeping the context around. + yield None + + # The try/finally is here so that if someone passes a WSGI level + # iterator in we're still running the cleanup logic. Generators + # don't need that because they are closed on their destruction + # automatically. + try: + for item in gen: + yield item + finally: + if hasattr(gen, 'close'): + gen.close() + + # The trick is to start the generator. Then the code execution runs until + # the first dummy None is yielded at which point the context was already + # pushed. This item is discarded. Then when the iteration continues the + # real generator is executed. + wrapped_g = generator() + next(wrapped_g) + return wrapped_g + + +def make_response(*args): + """Sometimes it is necessary to set additional headers in a view. Because + views do not have to return response objects but can return a value that + is converted into a response object by Flask itself, it becomes tricky to + add headers to it. This function can be called instead of using a return + and you will get a response object which you can use to attach headers. + + If view looked like this and you want to add a new header:: + + def index(): + return render_template('index.html', foo=42) + + You can now do something like this:: + + def index(): + response = make_response(render_template('index.html', foo=42)) + response.headers['X-Parachutes'] = 'parachutes are cool' + return response + + This function accepts the very same arguments you can return from a + view function. This for example creates a response with a 404 error + code:: + + response = make_response(render_template('not_found.html'), 404) + + The other use case of this function is to force the return value of a + view function into a response which is helpful with view + decorators:: + + response = make_response(view_function()) + response.headers['X-Parachutes'] = 'parachutes are cool' + + Internally this function does the following things: + + - if no arguments are passed, it creates a new response argument + - if one argument is passed, :meth:`flask.Flask.make_response` + is invoked with it. + - if more than one argument is passed, the arguments are passed + to the :meth:`flask.Flask.make_response` function as tuple. + + .. versionadded:: 0.6 + """ + if not args: + return current_app.response_class() + if len(args) == 1: + args = args[0] + return current_app.make_response(args) + + +def url_for(endpoint, **values): + """Generates a URL to the given endpoint with the method provided. + + Variable arguments that are unknown to the target endpoint are appended + to the generated URL as query arguments. If the value of a query argument + is ``None``, the whole pair is skipped. In case blueprints are active + you can shortcut references to the same blueprint by prefixing the + local endpoint with a dot (``.``). + + This will reference the index function local to the current blueprint:: + + url_for('.index') + + For more information, head over to the :ref:`Quickstart `. + + To integrate applications, :class:`Flask` has a hook to intercept URL build + errors through :attr:`Flask.url_build_error_handlers`. The `url_for` + function results in a :exc:`~werkzeug.routing.BuildError` when the current + app does not have a URL for the given endpoint and values. When it does, the + :data:`~flask.current_app` calls its :attr:`~Flask.url_build_error_handlers` if + it is not ``None``, which can return a string to use as the result of + `url_for` (instead of `url_for`'s default to raise the + :exc:`~werkzeug.routing.BuildError` exception) or re-raise the exception. + An example:: + + def external_url_handler(error, endpoint, values): + "Looks up an external URL when `url_for` cannot build a URL." + # This is an example of hooking the build_error_handler. + # Here, lookup_url is some utility function you've built + # which looks up the endpoint in some external URL registry. + url = lookup_url(endpoint, **values) + if url is None: + # External lookup did not have a URL. + # Re-raise the BuildError, in context of original traceback. + exc_type, exc_value, tb = sys.exc_info() + if exc_value is error: + raise exc_type, exc_value, tb + else: + raise error + # url_for will use this result, instead of raising BuildError. + return url + + app.url_build_error_handlers.append(external_url_handler) + + Here, `error` is the instance of :exc:`~werkzeug.routing.BuildError`, and + `endpoint` and `values` are the arguments passed into `url_for`. Note + that this is for building URLs outside the current application, and not for + handling 404 NotFound errors. + + .. versionadded:: 0.10 + The `_scheme` parameter was added. + + .. versionadded:: 0.9 + The `_anchor` and `_method` parameters were added. + + .. versionadded:: 0.9 + Calls :meth:`Flask.handle_build_error` on + :exc:`~werkzeug.routing.BuildError`. + + :param endpoint: the endpoint of the URL (name of the function) + :param values: the variable arguments of the URL rule + :param _external: if set to ``True``, an absolute URL is generated. Server + address can be changed via ``SERVER_NAME`` configuration variable which + defaults to `localhost`. + :param _scheme: a string specifying the desired URL scheme. The `_external` + parameter must be set to ``True`` or a :exc:`ValueError` is raised. The default + behavior uses the same scheme as the current request, or + ``PREFERRED_URL_SCHEME`` from the :ref:`app configuration ` if no + request context is available. As of Werkzeug 0.10, this also can be set + to an empty string to build protocol-relative URLs. + :param _anchor: if provided this is added as anchor to the URL. + :param _method: if provided this explicitly specifies an HTTP method. + """ + appctx = _app_ctx_stack.top + reqctx = _request_ctx_stack.top + + if appctx is None: + raise RuntimeError( + 'Attempted to generate a URL without the application context being' + ' pushed. This has to be executed when application context is' + ' available.' + ) + + # If request specific information is available we have some extra + # features that support "relative" URLs. + if reqctx is not None: + url_adapter = reqctx.url_adapter + blueprint_name = request.blueprint + + if endpoint[:1] == '.': + if blueprint_name is not None: + endpoint = blueprint_name + endpoint + else: + endpoint = endpoint[1:] + + external = values.pop('_external', False) + + # Otherwise go with the url adapter from the appctx and make + # the URLs external by default. + else: + url_adapter = appctx.url_adapter + + if url_adapter is None: + raise RuntimeError( + 'Application was not able to create a URL adapter for request' + ' independent URL generation. You might be able to fix this by' + ' setting the SERVER_NAME config variable.' + ) + + external = values.pop('_external', True) + + anchor = values.pop('_anchor', None) + method = values.pop('_method', None) + scheme = values.pop('_scheme', None) + appctx.app.inject_url_defaults(endpoint, values) + + # This is not the best way to deal with this but currently the + # underlying Werkzeug router does not support overriding the scheme on + # a per build call basis. + old_scheme = None + if scheme is not None: + if not external: + raise ValueError('When specifying _scheme, _external must be True') + old_scheme = url_adapter.url_scheme + url_adapter.url_scheme = scheme + + try: + try: + rv = url_adapter.build(endpoint, values, method=method, + force_external=external) + finally: + if old_scheme is not None: + url_adapter.url_scheme = old_scheme + except BuildError as error: + # We need to inject the values again so that the app callback can + # deal with that sort of stuff. + values['_external'] = external + values['_anchor'] = anchor + values['_method'] = method + values['_scheme'] = scheme + return appctx.app.handle_url_build_error(error, endpoint, values) + + if anchor is not None: + rv += '#' + url_quote(anchor) + return rv + + +def get_template_attribute(template_name, attribute): + """Loads a macro (or variable) a template exports. This can be used to + invoke a macro from within Python code. If you for example have a + template named :file:`_cider.html` with the following contents: + + .. sourcecode:: html+jinja + + {% macro hello(name) %}Hello {{ name }}!{% endmacro %} + + You can access this from Python code like this:: + + hello = get_template_attribute('_cider.html', 'hello') + return hello('World') + + .. versionadded:: 0.2 + + :param template_name: the name of the template + :param attribute: the name of the variable of macro to access + """ + return getattr(current_app.jinja_env.get_template(template_name).module, + attribute) + + +def flash(message, category='message'): + """Flashes a message to the next request. In order to remove the + flashed message from the session and to display it to the user, + the template has to call :func:`get_flashed_messages`. + + .. versionchanged:: 0.3 + `category` parameter added. + + :param message: the message to be flashed. + :param category: the category for the message. The following values + are recommended: ``'message'`` for any kind of message, + ``'error'`` for errors, ``'info'`` for information + messages and ``'warning'`` for warnings. However any + kind of string can be used as category. + """ + # Original implementation: + # + # session.setdefault('_flashes', []).append((category, message)) + # + # This assumed that changes made to mutable structures in the session are + # always in sync with the session object, which is not true for session + # implementations that use external storage for keeping their keys/values. + flashes = session.get('_flashes', []) + flashes.append((category, message)) + session['_flashes'] = flashes + message_flashed.send(current_app._get_current_object(), + message=message, category=category) + + +def get_flashed_messages(with_categories=False, category_filter=[]): + """Pulls all flashed messages from the session and returns them. + Further calls in the same request to the function will return + the same messages. By default just the messages are returned, + but when `with_categories` is set to ``True``, the return value will + be a list of tuples in the form ``(category, message)`` instead. + + Filter the flashed messages to one or more categories by providing those + categories in `category_filter`. This allows rendering categories in + separate html blocks. The `with_categories` and `category_filter` + arguments are distinct: + + * `with_categories` controls whether categories are returned with message + text (``True`` gives a tuple, where ``False`` gives just the message text). + * `category_filter` filters the messages down to only those matching the + provided categories. + + See :ref:`message-flashing-pattern` for examples. + + .. versionchanged:: 0.3 + `with_categories` parameter added. + + .. versionchanged:: 0.9 + `category_filter` parameter added. + + :param with_categories: set to ``True`` to also receive categories. + :param category_filter: whitelist of categories to limit return values + """ + flashes = _request_ctx_stack.top.flashes + if flashes is None: + _request_ctx_stack.top.flashes = flashes = session.pop('_flashes') \ + if '_flashes' in session else [] + if category_filter: + flashes = list(filter(lambda f: f[0] in category_filter, flashes)) + if not with_categories: + return [x[1] for x in flashes] + return flashes + + +def send_file(filename_or_fp, mimetype=None, as_attachment=False, + attachment_filename=None, add_etags=True, + cache_timeout=None, conditional=False, last_modified=None): + """Sends the contents of a file to the client. This will use the + most efficient method available and configured. By default it will + try to use the WSGI server's file_wrapper support. Alternatively + you can set the application's :attr:`~Flask.use_x_sendfile` attribute + to ``True`` to directly emit an ``X-Sendfile`` header. This however + requires support of the underlying webserver for ``X-Sendfile``. + + By default it will try to guess the mimetype for you, but you can + also explicitly provide one. For extra security you probably want + to send certain files as attachment (HTML for instance). The mimetype + guessing requires a `filename` or an `attachment_filename` to be + provided. + + ETags will also be attached automatically if a `filename` is provided. You + can turn this off by setting `add_etags=False`. + + If `conditional=True` and `filename` is provided, this method will try to + upgrade the response stream to support range requests. This will allow + the request to be answered with partial content response. + + Please never pass filenames to this function from user sources; + you should use :func:`send_from_directory` instead. + + .. versionadded:: 0.2 + + .. versionadded:: 0.5 + The `add_etags`, `cache_timeout` and `conditional` parameters were + added. The default behavior is now to attach etags. + + .. versionchanged:: 0.7 + mimetype guessing and etag support for file objects was + deprecated because it was unreliable. Pass a filename if you are + able to, otherwise attach an etag yourself. This functionality + will be removed in Flask 1.0 + + .. versionchanged:: 0.9 + cache_timeout pulls its default from application config, when None. + + .. versionchanged:: 0.12 + The filename is no longer automatically inferred from file objects. If + you want to use automatic mimetype and etag support, pass a filepath via + `filename_or_fp` or `attachment_filename`. + + .. versionchanged:: 0.12 + The `attachment_filename` is preferred over `filename` for MIME-type + detection. + + .. versionchanged:: 1.0 + UTF-8 filenames, as specified in `RFC 2231`_, are supported. + + .. _RFC 2231: https://tools.ietf.org/html/rfc2231#section-4 + + :param filename_or_fp: the filename of the file to send. + This is relative to the :attr:`~Flask.root_path` + if a relative path is specified. + Alternatively a file object might be provided in + which case ``X-Sendfile`` might not work and fall + back to the traditional method. Make sure that the + file pointer is positioned at the start of data to + send before calling :func:`send_file`. + :param mimetype: the mimetype of the file if provided. If a file path is + given, auto detection happens as fallback, otherwise an + error will be raised. + :param as_attachment: set to ``True`` if you want to send this file with + a ``Content-Disposition: attachment`` header. + :param attachment_filename: the filename for the attachment if it + differs from the file's filename. + :param add_etags: set to ``False`` to disable attaching of etags. + :param conditional: set to ``True`` to enable conditional responses. + + :param cache_timeout: the timeout in seconds for the headers. When ``None`` + (default), this value is set by + :meth:`~Flask.get_send_file_max_age` of + :data:`~flask.current_app`. + :param last_modified: set the ``Last-Modified`` header to this value, + a :class:`~datetime.datetime` or timestamp. + If a file was passed, this overrides its mtime. + """ + mtime = None + fsize = None + if isinstance(filename_or_fp, string_types): + filename = filename_or_fp + if not os.path.isabs(filename): + filename = os.path.join(current_app.root_path, filename) + file = None + if attachment_filename is None: + attachment_filename = os.path.basename(filename) + else: + file = filename_or_fp + filename = None + + if mimetype is None: + if attachment_filename is not None: + mimetype = mimetypes.guess_type(attachment_filename)[0] \ + or 'application/octet-stream' + + if mimetype is None: + raise ValueError( + 'Unable to infer MIME-type because no filename is available. ' + 'Please set either `attachment_filename`, pass a filepath to ' + '`filename_or_fp` or set your own MIME-type via `mimetype`.' + ) + + headers = Headers() + if as_attachment: + if attachment_filename is None: + raise TypeError('filename unavailable, required for ' + 'sending as attachment') + + try: + attachment_filename = attachment_filename.encode('latin-1') + except UnicodeEncodeError: + filenames = { + 'filename': unicodedata.normalize( + 'NFKD', attachment_filename).encode('latin-1', 'ignore'), + 'filename*': "UTF-8''%s" % url_quote(attachment_filename), + } + else: + filenames = {'filename': attachment_filename} + + headers.add('Content-Disposition', 'attachment', **filenames) + + if current_app.use_x_sendfile and filename: + if file is not None: + file.close() + headers['X-Sendfile'] = filename + fsize = os.path.getsize(filename) + headers['Content-Length'] = fsize + data = None + else: + if file is None: + file = open(filename, 'rb') + mtime = os.path.getmtime(filename) + fsize = os.path.getsize(filename) + headers['Content-Length'] = fsize + data = wrap_file(request.environ, file) + + rv = current_app.response_class(data, mimetype=mimetype, headers=headers, + direct_passthrough=True) + + if last_modified is not None: + rv.last_modified = last_modified + elif mtime is not None: + rv.last_modified = mtime + + rv.cache_control.public = True + if cache_timeout is None: + cache_timeout = current_app.get_send_file_max_age(filename) + if cache_timeout is not None: + rv.cache_control.max_age = cache_timeout + rv.expires = int(time() + cache_timeout) + + if add_etags and filename is not None: + from warnings import warn + + try: + rv.set_etag('%s-%s-%s' % ( + os.path.getmtime(filename), + os.path.getsize(filename), + adler32( + filename.encode('utf-8') if isinstance(filename, text_type) + else filename + ) & 0xffffffff + )) + except OSError: + warn('Access %s failed, maybe it does not exist, so ignore etags in ' + 'headers' % filename, stacklevel=2) + + if conditional: + try: + rv = rv.make_conditional(request, accept_ranges=True, + complete_length=fsize) + except RequestedRangeNotSatisfiable: + if file is not None: + file.close() + raise + # make sure we don't send x-sendfile for servers that + # ignore the 304 status code for x-sendfile. + if rv.status_code == 304: + rv.headers.pop('x-sendfile', None) + return rv + + +def safe_join(directory, *pathnames): + """Safely join `directory` and zero or more untrusted `pathnames` + components. + + Example usage:: + + @app.route('/wiki/') + def wiki_page(filename): + filename = safe_join(app.config['WIKI_FOLDER'], filename) + with open(filename, 'rb') as fd: + content = fd.read() # Read and process the file content... + + :param directory: the trusted base directory. + :param pathnames: the untrusted pathnames relative to that directory. + :raises: :class:`~werkzeug.exceptions.NotFound` if one or more passed + paths fall out of its boundaries. + """ + + parts = [directory] + + for filename in pathnames: + if filename != '': + filename = posixpath.normpath(filename) + + if ( + any(sep in filename for sep in _os_alt_seps) + or os.path.isabs(filename) + or filename == '..' + or filename.startswith('../') + ): + raise NotFound() + + parts.append(filename) + + return posixpath.join(*parts) + + +def send_from_directory(directory, filename, **options): + """Send a file from a given directory with :func:`send_file`. This + is a secure way to quickly expose static files from an upload folder + or something similar. + + Example usage:: + + @app.route('/uploads/') + def download_file(filename): + return send_from_directory(app.config['UPLOAD_FOLDER'], + filename, as_attachment=True) + + .. admonition:: Sending files and Performance + + It is strongly recommended to activate either ``X-Sendfile`` support in + your webserver or (if no authentication happens) to tell the webserver + to serve files for the given path on its own without calling into the + web application for improved performance. + + .. versionadded:: 0.5 + + :param directory: the directory where all the files are stored. + :param filename: the filename relative to that directory to + download. + :param options: optional keyword arguments that are directly + forwarded to :func:`send_file`. + """ + filename = safe_join(directory, filename) + if not os.path.isabs(filename): + filename = os.path.join(current_app.root_path, filename) + try: + if not os.path.isfile(filename): + raise NotFound() + except (TypeError, ValueError): + raise BadRequest() + options.setdefault('conditional', True) + return send_file(filename, **options) + + +def get_root_path(import_name): + """Returns the path to a package or cwd if that cannot be found. This + returns the path of a package or the folder that contains a module. + + Not to be confused with the package path returned by :func:`find_package`. + """ + # Module already imported and has a file attribute. Use that first. + mod = sys.modules.get(import_name) + if mod is not None and hasattr(mod, '__file__'): + return os.path.dirname(os.path.abspath(mod.__file__)) + + # Next attempt: check the loader. + loader = pkgutil.get_loader(import_name) + + # Loader does not exist or we're referring to an unloaded main module + # or a main module without path (interactive sessions), go with the + # current working directory. + if loader is None or import_name == '__main__': + return os.getcwd() + + # For .egg, zipimporter does not have get_filename until Python 2.7. + # Some other loaders might exhibit the same behavior. + if hasattr(loader, 'get_filename'): + filepath = loader.get_filename(import_name) + else: + # Fall back to imports. + __import__(import_name) + mod = sys.modules[import_name] + filepath = getattr(mod, '__file__', None) + + # If we don't have a filepath it might be because we are a + # namespace package. In this case we pick the root path from the + # first module that is contained in our package. + if filepath is None: + raise RuntimeError('No root path can be found for the provided ' + 'module "%s". This can happen because the ' + 'module came from an import hook that does ' + 'not provide file name information or because ' + 'it\'s a namespace package. In this case ' + 'the root path needs to be explicitly ' + 'provided.' % import_name) + + # filepath is import_name.py for a module, or __init__.py for a package. + return os.path.dirname(os.path.abspath(filepath)) + + +def _matching_loader_thinks_module_is_package(loader, mod_name): + """Given the loader that loaded a module and the module this function + attempts to figure out if the given module is actually a package. + """ + # If the loader can tell us if something is a package, we can + # directly ask the loader. + if hasattr(loader, 'is_package'): + return loader.is_package(mod_name) + # importlib's namespace loaders do not have this functionality but + # all the modules it loads are packages, so we can take advantage of + # this information. + elif (loader.__class__.__module__ == '_frozen_importlib' and + loader.__class__.__name__ == 'NamespaceLoader'): + return True + # Otherwise we need to fail with an error that explains what went + # wrong. + raise AttributeError( + ('%s.is_package() method is missing but is required by Flask of ' + 'PEP 302 import hooks. If you do not use import hooks and ' + 'you encounter this error please file a bug against Flask.') % + loader.__class__.__name__) + + +def find_package(import_name): + """Finds a package and returns the prefix (or None if the package is + not installed) as well as the folder that contains the package or + module as a tuple. The package path returned is the module that would + have to be added to the pythonpath in order to make it possible to + import the module. The prefix is the path below which a UNIX like + folder structure exists (lib, share etc.). + """ + root_mod_name = import_name.split('.')[0] + loader = pkgutil.get_loader(root_mod_name) + if loader is None or import_name == '__main__': + # import name is not found, or interactive/main module + package_path = os.getcwd() + else: + # For .egg, zipimporter does not have get_filename until Python 2.7. + if hasattr(loader, 'get_filename'): + filename = loader.get_filename(root_mod_name) + elif hasattr(loader, 'archive'): + # zipimporter's loader.archive points to the .egg or .zip + # archive filename is dropped in call to dirname below. + filename = loader.archive + else: + # At least one loader is missing both get_filename and archive: + # Google App Engine's HardenedModulesHook + # + # Fall back to imports. + __import__(import_name) + filename = sys.modules[import_name].__file__ + package_path = os.path.abspath(os.path.dirname(filename)) + + # In case the root module is a package we need to chop of the + # rightmost part. This needs to go through a helper function + # because of python 3.3 namespace packages. + if _matching_loader_thinks_module_is_package( + loader, root_mod_name): + package_path = os.path.dirname(package_path) + + site_parent, site_folder = os.path.split(package_path) + py_prefix = os.path.abspath(sys.prefix) + if package_path.startswith(py_prefix): + return py_prefix, package_path + elif site_folder.lower() == 'site-packages': + parent, folder = os.path.split(site_parent) + # Windows like installations + if folder.lower() == 'lib': + base_dir = parent + # UNIX like installations + elif os.path.basename(parent).lower() == 'lib': + base_dir = os.path.dirname(parent) + else: + base_dir = site_parent + return base_dir, package_path + return None, package_path + + +class locked_cached_property(object): + """A decorator that converts a function into a lazy property. The + function wrapped is called the first time to retrieve the result + and then that calculated result is used the next time you access + the value. Works like the one in Werkzeug but has a lock for + thread safety. + """ + + def __init__(self, func, name=None, doc=None): + self.__name__ = name or func.__name__ + self.__module__ = func.__module__ + self.__doc__ = doc or func.__doc__ + self.func = func + self.lock = RLock() + + def __get__(self, obj, type=None): + if obj is None: + return self + with self.lock: + value = obj.__dict__.get(self.__name__, _missing) + if value is _missing: + value = self.func(obj) + obj.__dict__[self.__name__] = value + return value + + +class _PackageBoundObject(object): + #: The name of the package or module that this app belongs to. Do not + #: change this once it is set by the constructor. + import_name = None + + #: Location of the template files to be added to the template lookup. + #: ``None`` if templates should not be added. + template_folder = None + + #: Absolute path to the package on the filesystem. Used to look up + #: resources contained in the package. + root_path = None + + def __init__(self, import_name, template_folder=None, root_path=None): + self.import_name = import_name + self.template_folder = template_folder + + if root_path is None: + root_path = get_root_path(self.import_name) + + self.root_path = root_path + self._static_folder = None + self._static_url_path = None + + def _get_static_folder(self): + if self._static_folder is not None: + return os.path.join(self.root_path, self._static_folder) + + def _set_static_folder(self, value): + self._static_folder = value + + static_folder = property( + _get_static_folder, _set_static_folder, + doc='The absolute path to the configured static folder.' + ) + del _get_static_folder, _set_static_folder + + def _get_static_url_path(self): + if self._static_url_path is not None: + return self._static_url_path + + if self.static_folder is not None: + return '/' + os.path.basename(self.static_folder) + + def _set_static_url_path(self, value): + self._static_url_path = value + + static_url_path = property( + _get_static_url_path, _set_static_url_path, + doc='The URL prefix that the static route will be registered for.' + ) + del _get_static_url_path, _set_static_url_path + + @property + def has_static_folder(self): + """This is ``True`` if the package bound object's container has a + folder for static files. + + .. versionadded:: 0.5 + """ + return self.static_folder is not None + + @locked_cached_property + def jinja_loader(self): + """The Jinja loader for this package bound object. + + .. versionadded:: 0.5 + """ + if self.template_folder is not None: + return FileSystemLoader(os.path.join(self.root_path, + self.template_folder)) + + def get_send_file_max_age(self, filename): + """Provides default cache_timeout for the :func:`send_file` functions. + + By default, this function returns ``SEND_FILE_MAX_AGE_DEFAULT`` from + the configuration of :data:`~flask.current_app`. + + Static file functions such as :func:`send_from_directory` use this + function, and :func:`send_file` calls this function on + :data:`~flask.current_app` when the given cache_timeout is ``None``. If a + cache_timeout is given in :func:`send_file`, that timeout is used; + otherwise, this method is called. + + This allows subclasses to change the behavior when sending files based + on the filename. For example, to set the cache timeout for .js files + to 60 seconds:: + + class MyFlask(flask.Flask): + def get_send_file_max_age(self, name): + if name.lower().endswith('.js'): + return 60 + return flask.Flask.get_send_file_max_age(self, name) + + .. versionadded:: 0.9 + """ + return total_seconds(current_app.send_file_max_age_default) + + def send_static_file(self, filename): + """Function used internally to send static files from the static + folder to the browser. + + .. versionadded:: 0.5 + """ + if not self.has_static_folder: + raise RuntimeError('No static folder for this object') + # Ensure get_send_file_max_age is called in all cases. + # Here, we ensure get_send_file_max_age is called for Blueprints. + cache_timeout = self.get_send_file_max_age(filename) + return send_from_directory(self.static_folder, filename, + cache_timeout=cache_timeout) + + def open_resource(self, resource, mode='rb'): + """Opens a resource from the application's resource folder. To see + how this works, consider the following folder structure:: + + /myapplication.py + /schema.sql + /static + /style.css + /templates + /layout.html + /index.html + + If you want to open the :file:`schema.sql` file you would do the + following:: + + with app.open_resource('schema.sql') as f: + contents = f.read() + do_something_with(contents) + + :param resource: the name of the resource. To access resources within + subfolders use forward slashes as separator. + :param mode: resource file opening mode, default is 'rb'. + """ + if mode not in ('r', 'rb'): + raise ValueError('Resources can only be opened for reading') + return open(os.path.join(self.root_path, resource), mode) + + +def total_seconds(td): + """Returns the total seconds from a timedelta object. + + :param timedelta td: the timedelta to be converted in seconds + + :returns: number of seconds + :rtype: int + """ + return td.days * 60 * 60 * 24 + td.seconds + + +def is_ip(value): + """Determine if the given string is an IP address. + + Python 2 on Windows doesn't provide ``inet_pton``, so this only + checks IPv4 addresses in that environment. + + :param value: value to check + :type value: str + + :return: True if string is an IP address + :rtype: bool + """ + if PY2 and os.name == 'nt': + try: + socket.inet_aton(value) + return True + except socket.error: + return False + + for family in (socket.AF_INET, socket.AF_INET6): + try: + socket.inet_pton(family, value) + except socket.error: + pass + else: + return True + + return False diff --git a/pyextra/flask/json/__init__.py b/pyextra/flask/json/__init__.py new file mode 100644 index 00000000000000..fbe6b92f0a3712 --- /dev/null +++ b/pyextra/flask/json/__init__.py @@ -0,0 +1,327 @@ +# -*- coding: utf-8 -*- +""" +flask.json +~~~~~~~~~~ + +:copyright: © 2010 by the Pallets team. +:license: BSD, see LICENSE for more details. +""" +import codecs +import io +import uuid +from datetime import date, datetime +from flask.globals import current_app, request +from flask._compat import text_type, PY2 + +from werkzeug.http import http_date +from jinja2 import Markup + +# Use the same json implementation as itsdangerous on which we +# depend anyways. +from itsdangerous import json as _json + + +# Figure out if simplejson escapes slashes. This behavior was changed +# from one version to another without reason. +_slash_escape = '\\/' not in _json.dumps('/') + + +__all__ = ['dump', 'dumps', 'load', 'loads', 'htmlsafe_dump', + 'htmlsafe_dumps', 'JSONDecoder', 'JSONEncoder', + 'jsonify'] + + +def _wrap_reader_for_text(fp, encoding): + if isinstance(fp.read(0), bytes): + fp = io.TextIOWrapper(io.BufferedReader(fp), encoding) + return fp + + +def _wrap_writer_for_text(fp, encoding): + try: + fp.write('') + except TypeError: + fp = io.TextIOWrapper(fp, encoding) + return fp + + +class JSONEncoder(_json.JSONEncoder): + """The default Flask JSON encoder. This one extends the default simplejson + encoder by also supporting ``datetime`` objects, ``UUID`` as well as + ``Markup`` objects which are serialized as RFC 822 datetime strings (same + as the HTTP date format). In order to support more data types override the + :meth:`default` method. + """ + + def default(self, o): + """Implement this method in a subclass such that it returns a + serializable object for ``o``, or calls the base implementation (to + raise a :exc:`TypeError`). + + For example, to support arbitrary iterators, you could implement + default like this:: + + def default(self, o): + try: + iterable = iter(o) + except TypeError: + pass + else: + return list(iterable) + return JSONEncoder.default(self, o) + """ + if isinstance(o, datetime): + return http_date(o.utctimetuple()) + if isinstance(o, date): + return http_date(o.timetuple()) + if isinstance(o, uuid.UUID): + return str(o) + if hasattr(o, '__html__'): + return text_type(o.__html__()) + return _json.JSONEncoder.default(self, o) + + +class JSONDecoder(_json.JSONDecoder): + """The default JSON decoder. This one does not change the behavior from + the default simplejson decoder. Consult the :mod:`json` documentation + for more information. This decoder is not only used for the load + functions of this module but also :attr:`~flask.Request`. + """ + + +def _dump_arg_defaults(kwargs): + """Inject default arguments for dump functions.""" + if current_app: + bp = current_app.blueprints.get(request.blueprint) if request else None + kwargs.setdefault( + 'cls', + bp.json_encoder if bp and bp.json_encoder + else current_app.json_encoder + ) + + if not current_app.config['JSON_AS_ASCII']: + kwargs.setdefault('ensure_ascii', False) + + kwargs.setdefault('sort_keys', current_app.config['JSON_SORT_KEYS']) + else: + kwargs.setdefault('sort_keys', True) + kwargs.setdefault('cls', JSONEncoder) + + +def _load_arg_defaults(kwargs): + """Inject default arguments for load functions.""" + if current_app: + bp = current_app.blueprints.get(request.blueprint) if request else None + kwargs.setdefault( + 'cls', + bp.json_decoder if bp and bp.json_decoder + else current_app.json_decoder + ) + else: + kwargs.setdefault('cls', JSONDecoder) + + +def detect_encoding(data): + """Detect which UTF codec was used to encode the given bytes. + + The latest JSON standard (:rfc:`8259`) suggests that only UTF-8 is + accepted. Older documents allowed 8, 16, or 32. 16 and 32 can be big + or little endian. Some editors or libraries may prepend a BOM. + + :param data: Bytes in unknown UTF encoding. + :return: UTF encoding name + """ + head = data[:4] + + if head[:3] == codecs.BOM_UTF8: + return 'utf-8-sig' + + if b'\x00' not in head: + return 'utf-8' + + if head in (codecs.BOM_UTF32_BE, codecs.BOM_UTF32_LE): + return 'utf-32' + + if head[:2] in (codecs.BOM_UTF16_BE, codecs.BOM_UTF16_LE): + return 'utf-16' + + if len(head) == 4: + if head[:3] == b'\x00\x00\x00': + return 'utf-32-be' + + if head[::2] == b'\x00\x00': + return 'utf-16-be' + + if head[1:] == b'\x00\x00\x00': + return 'utf-32-le' + + if head[1::2] == b'\x00\x00': + return 'utf-16-le' + + if len(head) == 2: + return 'utf-16-be' if head.startswith(b'\x00') else 'utf-16-le' + + return 'utf-8' + + +def dumps(obj, **kwargs): + """Serialize ``obj`` to a JSON formatted ``str`` by using the application's + configured encoder (:attr:`~flask.Flask.json_encoder`) if there is an + application on the stack. + + This function can return ``unicode`` strings or ascii-only bytestrings by + default which coerce into unicode strings automatically. That behavior by + default is controlled by the ``JSON_AS_ASCII`` configuration variable + and can be overridden by the simplejson ``ensure_ascii`` parameter. + """ + _dump_arg_defaults(kwargs) + encoding = kwargs.pop('encoding', None) + rv = _json.dumps(obj, **kwargs) + if encoding is not None and isinstance(rv, text_type): + rv = rv.encode(encoding) + return rv + + +def dump(obj, fp, **kwargs): + """Like :func:`dumps` but writes into a file object.""" + _dump_arg_defaults(kwargs) + encoding = kwargs.pop('encoding', None) + if encoding is not None: + fp = _wrap_writer_for_text(fp, encoding) + _json.dump(obj, fp, **kwargs) + + +def loads(s, **kwargs): + """Unserialize a JSON object from a string ``s`` by using the application's + configured decoder (:attr:`~flask.Flask.json_decoder`) if there is an + application on the stack. + """ + _load_arg_defaults(kwargs) + if isinstance(s, bytes): + encoding = kwargs.pop('encoding', None) + if encoding is None: + encoding = detect_encoding(s) + s = s.decode(encoding) + return _json.loads(s, **kwargs) + + +def load(fp, **kwargs): + """Like :func:`loads` but reads from a file object. + """ + _load_arg_defaults(kwargs) + if not PY2: + fp = _wrap_reader_for_text(fp, kwargs.pop('encoding', None) or 'utf-8') + return _json.load(fp, **kwargs) + + +def htmlsafe_dumps(obj, **kwargs): + """Works exactly like :func:`dumps` but is safe for use in `` + + + + +
+''' +FOOTER = u'''\ + +
+ +
+
+

Console Locked

+

+ The console is locked and needs to be unlocked by entering the PIN. + You can find the PIN printed out on the standard output of your + shell that runs the server. +

+

PIN: + + +

+
+
+ + +''' + +PAGE_HTML = HEADER + u'''\ +

%(exception_type)s

+
+

%(exception)s

+
+

Traceback (most recent call last)

+%(summary)s +
+
+

+ + This is the Copy/Paste friendly version of the traceback. You can also paste this traceback into + a gist: + +

+ +
+
+
+ The debugger caught an exception in your WSGI application. You can now + look at the traceback which led to the error. + If you enable JavaScript you can also use additional features such as code + execution (if the evalex feature is enabled), automatic pasting of the + exceptions and much more. +
+''' + FOOTER + ''' + +''' + +CONSOLE_HTML = HEADER + u'''\ +

Interactive Console

+
+In this console you can execute Python expressions in the context of the +application. The initial namespace was created by the debugger automatically. +
+
The Console requires JavaScript.
+''' + FOOTER + +SUMMARY_HTML = u'''\ +
+ %(title)s +
    %(frames)s
+ %(description)s +
+''' + +FRAME_HTML = u'''\ +
+

File "%(filename)s", + line %(lineno)s, + in %(function_name)s

+
%(lines)s
+
+''' + +SOURCE_LINE_HTML = u'''\ + + %(lineno)s + %(code)s + +''' + + +def render_console_html(secret, evalex_trusted=True): + return CONSOLE_HTML % { + 'evalex': 'true', + 'evalex_trusted': evalex_trusted and 'true' or 'false', + 'console': 'true', + 'title': 'Console', + 'secret': secret, + 'traceback_id': -1 + } + + +def get_current_traceback(ignore_system_exceptions=False, + show_hidden_frames=False, skip=0): + """Get the current exception info as `Traceback` object. Per default + calling this method will reraise system exceptions such as generator exit, + system exit or others. This behavior can be disabled by passing `False` + to the function as first parameter. + """ + exc_type, exc_value, tb = sys.exc_info() + if ignore_system_exceptions and exc_type in system_exceptions: + raise + for x in range_type(skip): + if tb.tb_next is None: + break + tb = tb.tb_next + tb = Traceback(exc_type, exc_value, tb) + if not show_hidden_frames: + tb.filter_hidden_frames() + return tb + + +class Line(object): + """Helper for the source renderer.""" + __slots__ = ('lineno', 'code', 'in_frame', 'current') + + def __init__(self, lineno, code): + self.lineno = lineno + self.code = code + self.in_frame = False + self.current = False + + def classes(self): + rv = ['line'] + if self.in_frame: + rv.append('in-frame') + if self.current: + rv.append('current') + return rv + classes = property(classes) + + def render(self): + return SOURCE_LINE_HTML % { + 'classes': u' '.join(self.classes), + 'lineno': self.lineno, + 'code': escape(self.code) + } + + +class Traceback(object): + """Wraps a traceback.""" + + def __init__(self, exc_type, exc_value, tb): + self.exc_type = exc_type + self.exc_value = exc_value + if not isinstance(exc_type, str): + exception_type = exc_type.__name__ + if exc_type.__module__ not in ('__builtin__', 'exceptions'): + exception_type = exc_type.__module__ + '.' + exception_type + else: + exception_type = exc_type + self.exception_type = exception_type + + # we only add frames to the list that are not hidden. This follows + # the the magic variables as defined by paste.exceptions.collector + self.frames = [] + while tb: + self.frames.append(Frame(exc_type, exc_value, tb)) + tb = tb.tb_next + + def filter_hidden_frames(self): + """Remove the frames according to the paste spec.""" + if not self.frames: + return + + new_frames = [] + hidden = False + for frame in self.frames: + hide = frame.hide + if hide in ('before', 'before_and_this'): + new_frames = [] + hidden = False + if hide == 'before_and_this': + continue + elif hide in ('reset', 'reset_and_this'): + hidden = False + if hide == 'reset_and_this': + continue + elif hide in ('after', 'after_and_this'): + hidden = True + if hide == 'after_and_this': + continue + elif hide or hidden: + continue + new_frames.append(frame) + + # if we only have one frame and that frame is from the codeop + # module, remove it. + if len(new_frames) == 1 and self.frames[0].module == 'codeop': + del self.frames[:] + + # if the last frame is missing something went terrible wrong :( + elif self.frames[-1] in new_frames: + self.frames[:] = new_frames + + def is_syntax_error(self): + """Is it a syntax error?""" + return isinstance(self.exc_value, SyntaxError) + is_syntax_error = property(is_syntax_error) + + def exception(self): + """String representation of the exception.""" + buf = traceback.format_exception_only(self.exc_type, self.exc_value) + rv = ''.join(buf).strip() + return rv.decode('utf-8', 'replace') if PY2 else rv + exception = property(exception) + + def log(self, logfile=None): + """Log the ASCII traceback into a file object.""" + if logfile is None: + logfile = sys.stderr + tb = self.plaintext.rstrip() + u'\n' + if PY2: + tb = tb.encode('utf-8', 'replace') + logfile.write(tb) + + def paste(self): + """Create a paste and return the paste id.""" + data = json.dumps({ + 'description': 'Werkzeug Internal Server Error', + 'public': False, + 'files': { + 'traceback.txt': { + 'content': self.plaintext + } + } + }).encode('utf-8') + try: + from urllib2 import urlopen + except ImportError: + from urllib.request import urlopen + rv = urlopen('https://api.github.com/gists', data=data) + resp = json.loads(rv.read().decode('utf-8')) + rv.close() + return { + 'url': resp['html_url'], + 'id': resp['id'] + } + + def render_summary(self, include_title=True): + """Render the traceback for the interactive console.""" + title = '' + frames = [] + classes = ['traceback'] + if not self.frames: + classes.append('noframe-traceback') + + if include_title: + if self.is_syntax_error: + title = u'Syntax Error' + else: + title = u'Traceback (most recent call last):' + + for frame in self.frames: + frames.append(u'%s' % ( + frame.info and u' title="%s"' % escape(frame.info) or u'', + frame.render() + )) + + if self.is_syntax_error: + description_wrapper = u'
%s
' + else: + description_wrapper = u'
%s
' + + return SUMMARY_HTML % { + 'classes': u' '.join(classes), + 'title': title and u'

%s

' % title or u'', + 'frames': u'\n'.join(frames), + 'description': description_wrapper % escape(self.exception) + } + + def render_full(self, evalex=False, secret=None, + evalex_trusted=True): + """Render the Full HTML page with the traceback info.""" + exc = escape(self.exception) + return PAGE_HTML % { + 'evalex': evalex and 'true' or 'false', + 'evalex_trusted': evalex_trusted and 'true' or 'false', + 'console': 'false', + 'title': exc, + 'exception': exc, + 'exception_type': escape(self.exception_type), + 'summary': self.render_summary(include_title=False), + 'plaintext': escape(self.plaintext), + 'plaintext_cs': re.sub('-{2,}', '-', self.plaintext), + 'traceback_id': self.id, + 'secret': secret + } + + def generate_plaintext_traceback(self): + """Like the plaintext attribute but returns a generator""" + yield u'Traceback (most recent call last):' + for frame in self.frames: + yield u' File "%s", line %s, in %s' % ( + frame.filename, + frame.lineno, + frame.function_name + ) + yield u' ' + frame.current_line.strip() + yield self.exception + + def plaintext(self): + return u'\n'.join(self.generate_plaintext_traceback()) + plaintext = cached_property(plaintext) + + id = property(lambda x: id(x)) + + +class Frame(object): + + """A single frame in a traceback.""" + + def __init__(self, exc_type, exc_value, tb): + self.lineno = tb.tb_lineno + self.function_name = tb.tb_frame.f_code.co_name + self.locals = tb.tb_frame.f_locals + self.globals = tb.tb_frame.f_globals + + fn = inspect.getsourcefile(tb) or inspect.getfile(tb) + if fn[-4:] in ('.pyo', '.pyc'): + fn = fn[:-1] + # if it's a file on the file system resolve the real filename. + if os.path.isfile(fn): + fn = os.path.realpath(fn) + self.filename = to_unicode(fn, get_filesystem_encoding()) + self.module = self.globals.get('__name__') + self.loader = self.globals.get('__loader__') + self.code = tb.tb_frame.f_code + + # support for paste's traceback extensions + self.hide = self.locals.get('__traceback_hide__', False) + info = self.locals.get('__traceback_info__') + if info is not None: + try: + info = text_type(info) + except UnicodeError: + info = str(info).decode('utf-8', 'replace') + self.info = info + + def render(self): + """Render a single frame in a traceback.""" + return FRAME_HTML % { + 'id': self.id, + 'filename': escape(self.filename), + 'lineno': self.lineno, + 'function_name': escape(self.function_name), + 'lines': self.render_line_context(), + } + + def render_line_context(self): + before, current, after = self.get_context_lines() + rv = [] + + def render_line(line, cls): + line = line.expandtabs().rstrip() + stripped_line = line.strip() + prefix = len(line) - len(stripped_line) + rv.append( + '
%s%s
' % ( + cls, ' ' * prefix, escape(stripped_line) or ' ')) + + for line in before: + render_line(line, 'before') + render_line(current, 'current') + for line in after: + render_line(line, 'after') + + return '\n'.join(rv) + + def get_annotated_lines(self): + """Helper function that returns lines with extra information.""" + lines = [Line(idx + 1, x) for idx, x in enumerate(self.sourcelines)] + + # find function definition and mark lines + if hasattr(self.code, 'co_firstlineno'): + lineno = self.code.co_firstlineno - 1 + while lineno > 0: + if _funcdef_re.match(lines[lineno].code): + break + lineno -= 1 + try: + offset = len(inspect.getblock([x.code + '\n' for x + in lines[lineno:]])) + except TokenError: + offset = 0 + for line in lines[lineno:lineno + offset]: + line.in_frame = True + + # mark current line + try: + lines[self.lineno - 1].current = True + except IndexError: + pass + + return lines + + def eval(self, code, mode='single'): + """Evaluate code in the context of the frame.""" + if isinstance(code, string_types): + if PY2 and isinstance(code, unicode): # noqa + code = UTF8_COOKIE + code.encode('utf-8') + code = compile(code, '', mode) + return eval(code, self.globals, self.locals) + + @cached_property + def sourcelines(self): + """The sourcecode of the file as list of unicode strings.""" + # get sourcecode from loader or file + source = None + if self.loader is not None: + try: + if hasattr(self.loader, 'get_source'): + source = self.loader.get_source(self.module) + elif hasattr(self.loader, 'get_source_by_code'): + source = self.loader.get_source_by_code(self.code) + except Exception: + # we munch the exception so that we don't cause troubles + # if the loader is broken. + pass + + if source is None: + try: + f = open(to_native(self.filename, get_filesystem_encoding()), + mode='rb') + except IOError: + return [] + try: + source = f.read() + finally: + f.close() + + # already unicode? return right away + if isinstance(source, text_type): + return source.splitlines() + + # yes. it should be ascii, but we don't want to reject too many + # characters in the debugger if something breaks + charset = 'utf-8' + if source.startswith(UTF8_COOKIE): + source = source[3:] + else: + for idx, match in enumerate(_line_re.finditer(source)): + match = _coding_re.search(match.group()) + if match is not None: + charset = match.group(1) + break + if idx > 1: + break + + # on broken cookies we fall back to utf-8 too + charset = to_native(charset) + try: + codecs.lookup(charset) + except LookupError: + charset = 'utf-8' + + return source.decode(charset, 'replace').splitlines() + + def get_context_lines(self, context=5): + before = self.sourcelines[self.lineno - context - 1:self.lineno - 1] + past = self.sourcelines[self.lineno:self.lineno + context] + return ( + before, + self.current_line, + past, + ) + + @property + def current_line(self): + try: + return self.sourcelines[self.lineno - 1] + except IndexError: + return u'' + + @cached_property + def console(self): + return Console(self.globals, self.locals) + + id = property(lambda x: id(x)) diff --git a/pyextra/werkzeug/exceptions.py b/pyextra/werkzeug/exceptions.py new file mode 100644 index 00000000000000..1d68185a9b7be1 --- /dev/null +++ b/pyextra/werkzeug/exceptions.py @@ -0,0 +1,719 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.exceptions + ~~~~~~~~~~~~~~~~~~~ + + This module implements a number of Python exceptions you can raise from + within your views to trigger a standard non-200 response. + + + Usage Example + ------------- + + :: + + from werkzeug.wrappers import BaseRequest + from werkzeug.wsgi import responder + from werkzeug.exceptions import HTTPException, NotFound + + def view(request): + raise NotFound() + + @responder + def application(environ, start_response): + request = BaseRequest(environ) + try: + return view(request) + except HTTPException as e: + return e + + + As you can see from this example those exceptions are callable WSGI + applications. Because of Python 2.4 compatibility those do not extend + from the response objects but only from the python exception class. + + As a matter of fact they are not Werkzeug response objects. However you + can get a response object by calling ``get_response()`` on a HTTP + exception. + + Keep in mind that you have to pass an environment to ``get_response()`` + because some errors fetch additional information from the WSGI + environment. + + If you want to hook in a different exception page to say, a 404 status + code, you can add a second except for a specific subclass of an error:: + + @responder + def application(environ, start_response): + request = BaseRequest(environ) + try: + return view(request) + except NotFound, e: + return not_found(request) + except HTTPException, e: + return e + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import sys + +# Because of bootstrapping reasons we need to manually patch ourselves +# onto our parent module. +import werkzeug +werkzeug.exceptions = sys.modules[__name__] + +from werkzeug._internal import _get_environ +from werkzeug._compat import iteritems, integer_types, text_type, \ + implements_to_string + +from werkzeug.wrappers import Response + + +@implements_to_string +class HTTPException(Exception): + + """ + Baseclass for all HTTP exceptions. This exception can be called as WSGI + application to render a default error page or you can catch the subclasses + of it independently and render nicer error messages. + """ + + code = None + description = None + + def __init__(self, description=None, response=None): + Exception.__init__(self) + if description is not None: + self.description = description + self.response = response + + @classmethod + def wrap(cls, exception, name=None): + """This method returns a new subclass of the exception provided that + also is a subclass of `BadRequest`. + """ + class newcls(cls, exception): + + def __init__(self, arg=None, *args, **kwargs): + cls.__init__(self, *args, **kwargs) + exception.__init__(self, arg) + newcls.__module__ = sys._getframe(1).f_globals.get('__name__') + newcls.__name__ = name or cls.__name__ + exception.__name__ + return newcls + + @property + def name(self): + """The status name.""" + return HTTP_STATUS_CODES.get(self.code, 'Unknown Error') + + def get_description(self, environ=None): + """Get the description.""" + return u'

%s

' % escape(self.description) + + def get_body(self, environ=None): + """Get the HTML body.""" + return text_type(( + u'\n' + u'%(code)s %(name)s\n' + u'

%(name)s

\n' + u'%(description)s\n' + ) % { + 'code': self.code, + 'name': escape(self.name), + 'description': self.get_description(environ) + }) + + def get_headers(self, environ=None): + """Get a list of headers.""" + return [('Content-Type', 'text/html')] + + def get_response(self, environ=None): + """Get a response object. If one was passed to the exception + it's returned directly. + + :param environ: the optional environ for the request. This + can be used to modify the response depending + on how the request looked like. + :return: a :class:`Response` object or a subclass thereof. + """ + if self.response is not None: + return self.response + if environ is not None: + environ = _get_environ(environ) + headers = self.get_headers(environ) + return Response(self.get_body(environ), self.code, headers) + + def __call__(self, environ, start_response): + """Call the exception as WSGI application. + + :param environ: the WSGI environment. + :param start_response: the response callable provided by the WSGI + server. + """ + response = self.get_response(environ) + return response(environ, start_response) + + def __str__(self): + code = self.code if self.code is not None else '???' + return '%s %s: %s' % (code, self.name, self.description) + + def __repr__(self): + code = self.code if self.code is not None else '???' + return "<%s '%s: %s'>" % (self.__class__.__name__, code, self.name) + + +class BadRequest(HTTPException): + + """*400* `Bad Request` + + Raise if the browser sends something to the application the application + or server cannot handle. + """ + code = 400 + description = ( + 'The browser (or proxy) sent a request that this server could ' + 'not understand.' + ) + + +class ClientDisconnected(BadRequest): + + """Internal exception that is raised if Werkzeug detects a disconnected + client. Since the client is already gone at that point attempting to + send the error message to the client might not work and might ultimately + result in another exception in the server. Mainly this is here so that + it is silenced by default as far as Werkzeug is concerned. + + Since disconnections cannot be reliably detected and are unspecified + by WSGI to a large extent this might or might not be raised if a client + is gone. + + .. versionadded:: 0.8 + """ + + +class SecurityError(BadRequest): + + """Raised if something triggers a security error. This is otherwise + exactly like a bad request error. + + .. versionadded:: 0.9 + """ + + +class BadHost(BadRequest): + + """Raised if the submitted host is badly formatted. + + .. versionadded:: 0.11.2 + """ + + +class Unauthorized(HTTPException): + + """*401* `Unauthorized` + + Raise if the user is not authorized. Also used if you want to use HTTP + basic auth. + """ + code = 401 + description = ( + 'The server could not verify that you are authorized to access ' + 'the URL requested. You either supplied the wrong credentials (e.g. ' + 'a bad password), or your browser doesn\'t understand how to supply ' + 'the credentials required.' + ) + + +class Forbidden(HTTPException): + + """*403* `Forbidden` + + Raise if the user doesn't have the permission for the requested resource + but was authenticated. + """ + code = 403 + description = ( + 'You don\'t have the permission to access the requested resource. ' + 'It is either read-protected or not readable by the server.' + ) + + +class NotFound(HTTPException): + + """*404* `Not Found` + + Raise if a resource does not exist and never existed. + """ + code = 404 + description = ( + 'The requested URL was not found on the server. ' + 'If you entered the URL manually please check your spelling and ' + 'try again.' + ) + + +class MethodNotAllowed(HTTPException): + + """*405* `Method Not Allowed` + + Raise if the server used a method the resource does not handle. For + example `POST` if the resource is view only. Especially useful for REST. + + The first argument for this exception should be a list of allowed methods. + Strictly speaking the response would be invalid if you don't provide valid + methods in the header which you can do with that list. + """ + code = 405 + description = 'The method is not allowed for the requested URL.' + + def __init__(self, valid_methods=None, description=None): + """Takes an optional list of valid http methods + starting with werkzeug 0.3 the list will be mandatory.""" + HTTPException.__init__(self, description) + self.valid_methods = valid_methods + + def get_headers(self, environ): + headers = HTTPException.get_headers(self, environ) + if self.valid_methods: + headers.append(('Allow', ', '.join(self.valid_methods))) + return headers + + +class NotAcceptable(HTTPException): + + """*406* `Not Acceptable` + + Raise if the server can't return any content conforming to the + `Accept` headers of the client. + """ + code = 406 + + description = ( + 'The resource identified by the request is only capable of ' + 'generating response entities which have content characteristics ' + 'not acceptable according to the accept headers sent in the ' + 'request.' + ) + + +class RequestTimeout(HTTPException): + + """*408* `Request Timeout` + + Raise to signalize a timeout. + """ + code = 408 + description = ( + 'The server closed the network connection because the browser ' + 'didn\'t finish the request within the specified time.' + ) + + +class Conflict(HTTPException): + + """*409* `Conflict` + + Raise to signal that a request cannot be completed because it conflicts + with the current state on the server. + + .. versionadded:: 0.7 + """ + code = 409 + description = ( + 'A conflict happened while processing the request. The resource ' + 'might have been modified while the request was being processed.' + ) + + +class Gone(HTTPException): + + """*410* `Gone` + + Raise if a resource existed previously and went away without new location. + """ + code = 410 + description = ( + 'The requested URL is no longer available on this server and there ' + 'is no forwarding address. If you followed a link from a foreign ' + 'page, please contact the author of this page.' + ) + + +class LengthRequired(HTTPException): + + """*411* `Length Required` + + Raise if the browser submitted data but no ``Content-Length`` header which + is required for the kind of processing the server does. + """ + code = 411 + description = ( + 'A request with this method requires a valid Content-' + 'Length header.' + ) + + +class PreconditionFailed(HTTPException): + + """*412* `Precondition Failed` + + Status code used in combination with ``If-Match``, ``If-None-Match``, or + ``If-Unmodified-Since``. + """ + code = 412 + description = ( + 'The precondition on the request for the URL failed positive ' + 'evaluation.' + ) + + +class RequestEntityTooLarge(HTTPException): + + """*413* `Request Entity Too Large` + + The status code one should return if the data submitted exceeded a given + limit. + """ + code = 413 + description = ( + 'The data value transmitted exceeds the capacity limit.' + ) + + +class RequestURITooLarge(HTTPException): + + """*414* `Request URI Too Large` + + Like *413* but for too long URLs. + """ + code = 414 + description = ( + 'The length of the requested URL exceeds the capacity limit ' + 'for this server. The request cannot be processed.' + ) + + +class UnsupportedMediaType(HTTPException): + + """*415* `Unsupported Media Type` + + The status code returned if the server is unable to handle the media type + the client transmitted. + """ + code = 415 + description = ( + 'The server does not support the media type transmitted in ' + 'the request.' + ) + + +class RequestedRangeNotSatisfiable(HTTPException): + + """*416* `Requested Range Not Satisfiable` + + The client asked for an invalid part of the file. + + .. versionadded:: 0.7 + """ + code = 416 + description = ( + 'The server cannot provide the requested range.' + ) + + def __init__(self, length=None, units="bytes", description=None): + """Takes an optional `Content-Range` header value based on ``length`` + parameter. + """ + HTTPException.__init__(self, description) + self.length = length + self.units = units + + def get_headers(self, environ): + headers = HTTPException.get_headers(self, environ) + if self.length is not None: + headers.append( + ('Content-Range', '%s */%d' % (self.units, self.length))) + return headers + + +class ExpectationFailed(HTTPException): + + """*417* `Expectation Failed` + + The server cannot meet the requirements of the Expect request-header. + + .. versionadded:: 0.7 + """ + code = 417 + description = ( + 'The server could not meet the requirements of the Expect header' + ) + + +class ImATeapot(HTTPException): + + """*418* `I'm a teapot` + + The server should return this if it is a teapot and someone attempted + to brew coffee with it. + + .. versionadded:: 0.7 + """ + code = 418 + description = ( + 'This server is a teapot, not a coffee machine' + ) + + +class UnprocessableEntity(HTTPException): + + """*422* `Unprocessable Entity` + + Used if the request is well formed, but the instructions are otherwise + incorrect. + """ + code = 422 + description = ( + 'The request was well-formed but was unable to be followed ' + 'due to semantic errors.' + ) + + +class Locked(HTTPException): + + """*423* `Locked` + + Used if the resource that is being accessed is locked. + """ + code = 423 + description = ( + 'The resource that is being accessed is locked.' + ) + + +class PreconditionRequired(HTTPException): + + """*428* `Precondition Required` + + The server requires this request to be conditional, typically to prevent + the lost update problem, which is a race condition between two or more + clients attempting to update a resource through PUT or DELETE. By requiring + each client to include a conditional header ("If-Match" or "If-Unmodified- + Since") with the proper value retained from a recent GET request, the + server ensures that each client has at least seen the previous revision of + the resource. + """ + code = 428 + description = ( + 'This request is required to be conditional; try using "If-Match" ' + 'or "If-Unmodified-Since".' + ) + + +class TooManyRequests(HTTPException): + + """*429* `Too Many Requests` + + The server is limiting the rate at which this user receives responses, and + this request exceeds that rate. (The server may use any convenient method + to identify users and their request rates). The server may include a + "Retry-After" header to indicate how long the user should wait before + retrying. + """ + code = 429 + description = ( + 'This user has exceeded an allotted request count. Try again later.' + ) + + +class RequestHeaderFieldsTooLarge(HTTPException): + + """*431* `Request Header Fields Too Large` + + The server refuses to process the request because the header fields are too + large. One or more individual fields may be too large, or the set of all + headers is too large. + """ + code = 431 + description = ( + 'One or more header fields exceeds the maximum size.' + ) + + +class UnavailableForLegalReasons(HTTPException): + + """*451* `Unavailable For Legal Reasons` + + This status code indicates that the server is denying access to the + resource as a consequence of a legal demand. + """ + code = 451 + description = ( + 'Unavailable for legal reasons.' + ) + + +class InternalServerError(HTTPException): + + """*500* `Internal Server Error` + + Raise if an internal server error occurred. This is a good fallback if an + unknown error occurred in the dispatcher. + """ + code = 500 + description = ( + 'The server encountered an internal error and was unable to ' + 'complete your request. Either the server is overloaded or there ' + 'is an error in the application.' + ) + + +class NotImplemented(HTTPException): + + """*501* `Not Implemented` + + Raise if the application does not support the action requested by the + browser. + """ + code = 501 + description = ( + 'The server does not support the action requested by the ' + 'browser.' + ) + + +class BadGateway(HTTPException): + + """*502* `Bad Gateway` + + If you do proxying in your application you should return this status code + if you received an invalid response from the upstream server it accessed + in attempting to fulfill the request. + """ + code = 502 + description = ( + 'The proxy server received an invalid response from an upstream ' + 'server.' + ) + + +class ServiceUnavailable(HTTPException): + + """*503* `Service Unavailable` + + Status code you should return if a service is temporarily unavailable. + """ + code = 503 + description = ( + 'The server is temporarily unable to service your request due to ' + 'maintenance downtime or capacity problems. Please try again ' + 'later.' + ) + + +class GatewayTimeout(HTTPException): + + """*504* `Gateway Timeout` + + Status code you should return if a connection to an upstream server + times out. + """ + code = 504 + description = ( + 'The connection to an upstream server timed out.' + ) + + +class HTTPVersionNotSupported(HTTPException): + + """*505* `HTTP Version Not Supported` + + The server does not support the HTTP protocol version used in the request. + """ + code = 505 + description = ( + 'The server does not support the HTTP protocol version used in the ' + 'request.' + ) + + +default_exceptions = {} +__all__ = ['HTTPException'] + + +def _find_exceptions(): + for name, obj in iteritems(globals()): + try: + is_http_exception = issubclass(obj, HTTPException) + except TypeError: + is_http_exception = False + if not is_http_exception or obj.code is None: + continue + __all__.append(obj.__name__) + old_obj = default_exceptions.get(obj.code, None) + if old_obj is not None and issubclass(obj, old_obj): + continue + default_exceptions[obj.code] = obj +_find_exceptions() +del _find_exceptions + + +class Aborter(object): + + """ + When passed a dict of code -> exception items it can be used as + callable that raises exceptions. If the first argument to the + callable is an integer it will be looked up in the mapping, if it's + a WSGI application it will be raised in a proxy exception. + + The rest of the arguments are forwarded to the exception constructor. + """ + + def __init__(self, mapping=None, extra=None): + if mapping is None: + mapping = default_exceptions + self.mapping = dict(mapping) + if extra is not None: + self.mapping.update(extra) + + def __call__(self, code, *args, **kwargs): + if not args and not kwargs and not isinstance(code, integer_types): + raise HTTPException(response=code) + if code not in self.mapping: + raise LookupError('no exception for %r' % code) + raise self.mapping[code](*args, **kwargs) + + +def abort(status, *args, **kwargs): + ''' + Raises an :py:exc:`HTTPException` for the given status code or WSGI + application:: + + abort(404) # 404 Not Found + abort(Response('Hello World')) + + Can be passed a WSGI application or a status code. If a status code is + given it's looked up in the list of exceptions and will raise that + exception, if passed a WSGI application it will wrap it in a proxy WSGI + exception and raise that:: + + abort(404) + abort(Response('Hello World')) + + ''' + return _aborter(status, *args, **kwargs) + +_aborter = Aborter() + + +#: an exception that is used internally to signal both a key error and a +#: bad request. Used by a lot of the datastructures. +BadRequestKeyError = BadRequest.wrap(KeyError) + + +# imported here because of circular dependencies of werkzeug.utils +from werkzeug.utils import escape +from werkzeug.http import HTTP_STATUS_CODES diff --git a/pyextra/werkzeug/filesystem.py b/pyextra/werkzeug/filesystem.py new file mode 100644 index 00000000000000..62467465553477 --- /dev/null +++ b/pyextra/werkzeug/filesystem.py @@ -0,0 +1,66 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.filesystem + ~~~~~~~~~~~~~~~~~~~ + + Various utilities for the local filesystem. + + :copyright: (c) 2015 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" + +import codecs +import sys +import warnings + +# We do not trust traditional unixes. +has_likely_buggy_unicode_filesystem = \ + sys.platform.startswith('linux') or 'bsd' in sys.platform + + +def _is_ascii_encoding(encoding): + """ + Given an encoding this figures out if the encoding is actually ASCII (which + is something we don't actually want in most cases). This is necessary + because ASCII comes under many names such as ANSI_X3.4-1968. + """ + if encoding is None: + return False + try: + return codecs.lookup(encoding).name == 'ascii' + except LookupError: + return False + + +class BrokenFilesystemWarning(RuntimeWarning, UnicodeWarning): + '''The warning used by Werkzeug to signal a broken filesystem. Will only be + used once per runtime.''' + + +_warned_about_filesystem_encoding = False + + +def get_filesystem_encoding(): + """ + Returns the filesystem encoding that should be used. Note that this is + different from the Python understanding of the filesystem encoding which + might be deeply flawed. Do not use this value against Python's unicode APIs + because it might be different. See :ref:`filesystem-encoding` for the exact + behavior. + + The concept of a filesystem encoding in generally is not something you + should rely on. As such if you ever need to use this function except for + writing wrapper code reconsider. + """ + global _warned_about_filesystem_encoding + rv = sys.getfilesystemencoding() + if has_likely_buggy_unicode_filesystem and not rv \ + or _is_ascii_encoding(rv): + if not _warned_about_filesystem_encoding: + warnings.warn( + 'Detected a misconfigured UNIX filesystem: Will use UTF-8 as ' + 'filesystem encoding instead of {0!r}'.format(rv), + BrokenFilesystemWarning) + _warned_about_filesystem_encoding = True + return 'utf-8' + return rv diff --git a/pyextra/werkzeug/formparser.py b/pyextra/werkzeug/formparser.py new file mode 100644 index 00000000000000..c56859e905d65b --- /dev/null +++ b/pyextra/werkzeug/formparser.py @@ -0,0 +1,534 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.formparser + ~~~~~~~~~~~~~~~~~~~ + + This module implements the form parsing. It supports url-encoded forms + as well as non-nested multipart uploads. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re +import codecs + +# there are some platforms where SpooledTemporaryFile is not available. +# In that case we need to provide a fallback. +try: + from tempfile import SpooledTemporaryFile +except ImportError: + from tempfile import TemporaryFile + SpooledTemporaryFile = None + +from itertools import chain, repeat, tee +from functools import update_wrapper + +from werkzeug._compat import to_native, text_type, BytesIO +from werkzeug.urls import url_decode_stream +from werkzeug.wsgi import make_line_iter, \ + get_input_stream, get_content_length +from werkzeug.datastructures import Headers, FileStorage, MultiDict +from werkzeug.http import parse_options_header + + +#: an iterator that yields empty strings +_empty_string_iter = repeat('') + +#: a regular expression for multipart boundaries +_multipart_boundary_re = re.compile('^[ -~]{0,200}[!-~]$') + +#: supported http encodings that are also available in python we support +#: for multipart messages. +_supported_multipart_encodings = frozenset(['base64', 'quoted-printable']) + + +def default_stream_factory(total_content_length, filename, content_type, + content_length=None): + """The stream factory that is used per default.""" + max_size = 1024 * 500 + if SpooledTemporaryFile is not None: + return SpooledTemporaryFile(max_size=max_size, mode='wb+') + if total_content_length is None or total_content_length > max_size: + return TemporaryFile('wb+') + return BytesIO() + + +def parse_form_data(environ, stream_factory=None, charset='utf-8', + errors='replace', max_form_memory_size=None, + max_content_length=None, cls=None, + silent=True): + """Parse the form data in the environ and return it as tuple in the form + ``(stream, form, files)``. You should only call this method if the + transport method is `POST`, `PUT`, or `PATCH`. + + If the mimetype of the data transmitted is `multipart/form-data` the + files multidict will be filled with `FileStorage` objects. If the + mimetype is unknown the input stream is wrapped and returned as first + argument, else the stream is empty. + + This is a shortcut for the common usage of :class:`FormDataParser`. + + Have a look at :ref:`dealing-with-request-data` for more details. + + .. versionadded:: 0.5 + The `max_form_memory_size`, `max_content_length` and + `cls` parameters were added. + + .. versionadded:: 0.5.1 + The optional `silent` flag was added. + + :param environ: the WSGI environment to be used for parsing. + :param stream_factory: An optional callable that returns a new read and + writeable file descriptor. This callable works + the same as :meth:`~BaseResponse._get_file_stream`. + :param charset: The character set for URL and url encoded form data. + :param errors: The encoding error behavior. + :param max_form_memory_size: the maximum number of bytes to be accepted for + in-memory stored form data. If the data + exceeds the value specified an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param max_content_length: If this is provided and the transmitted data + is longer than this value an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + :param silent: If set to False parsing errors will not be caught. + :return: A tuple in the form ``(stream, form, files)``. + """ + return FormDataParser(stream_factory, charset, errors, + max_form_memory_size, max_content_length, + cls, silent).parse_from_environ(environ) + + +def exhaust_stream(f): + """Helper decorator for methods that exhausts the stream on return.""" + + def wrapper(self, stream, *args, **kwargs): + try: + return f(self, stream, *args, **kwargs) + finally: + exhaust = getattr(stream, 'exhaust', None) + if exhaust is not None: + exhaust() + else: + while 1: + chunk = stream.read(1024 * 64) + if not chunk: + break + return update_wrapper(wrapper, f) + + +class FormDataParser(object): + + """This class implements parsing of form data for Werkzeug. By itself + it can parse multipart and url encoded form data. It can be subclassed + and extended but for most mimetypes it is a better idea to use the + untouched stream and expose it as separate attributes on a request + object. + + .. versionadded:: 0.8 + + :param stream_factory: An optional callable that returns a new read and + writeable file descriptor. This callable works + the same as :meth:`~BaseResponse._get_file_stream`. + :param charset: The character set for URL and url encoded form data. + :param errors: The encoding error behavior. + :param max_form_memory_size: the maximum number of bytes to be accepted for + in-memory stored form data. If the data + exceeds the value specified an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param max_content_length: If this is provided and the transmitted data + is longer than this value an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + :param silent: If set to False parsing errors will not be caught. + """ + + def __init__(self, stream_factory=None, charset='utf-8', + errors='replace', max_form_memory_size=None, + max_content_length=None, cls=None, + silent=True): + if stream_factory is None: + stream_factory = default_stream_factory + self.stream_factory = stream_factory + self.charset = charset + self.errors = errors + self.max_form_memory_size = max_form_memory_size + self.max_content_length = max_content_length + if cls is None: + cls = MultiDict + self.cls = cls + self.silent = silent + + def get_parse_func(self, mimetype, options): + return self.parse_functions.get(mimetype) + + def parse_from_environ(self, environ): + """Parses the information from the environment as form data. + + :param environ: the WSGI environment to be used for parsing. + :return: A tuple in the form ``(stream, form, files)``. + """ + content_type = environ.get('CONTENT_TYPE', '') + content_length = get_content_length(environ) + mimetype, options = parse_options_header(content_type) + return self.parse(get_input_stream(environ), mimetype, + content_length, options) + + def parse(self, stream, mimetype, content_length, options=None): + """Parses the information from the given stream, mimetype, + content length and mimetype parameters. + + :param stream: an input stream + :param mimetype: the mimetype of the data + :param content_length: the content length of the incoming data + :param options: optional mimetype parameters (used for + the multipart boundary for instance) + :return: A tuple in the form ``(stream, form, files)``. + """ + if self.max_content_length is not None and \ + content_length is not None and \ + content_length > self.max_content_length: + raise exceptions.RequestEntityTooLarge() + if options is None: + options = {} + + parse_func = self.get_parse_func(mimetype, options) + if parse_func is not None: + try: + return parse_func(self, stream, mimetype, + content_length, options) + except ValueError: + if not self.silent: + raise + + return stream, self.cls(), self.cls() + + @exhaust_stream + def _parse_multipart(self, stream, mimetype, content_length, options): + parser = MultiPartParser(self.stream_factory, self.charset, self.errors, + max_form_memory_size=self.max_form_memory_size, + cls=self.cls) + boundary = options.get('boundary') + if boundary is None: + raise ValueError('Missing boundary') + if isinstance(boundary, text_type): + boundary = boundary.encode('ascii') + form, files = parser.parse(stream, boundary, content_length) + return stream, form, files + + @exhaust_stream + def _parse_urlencoded(self, stream, mimetype, content_length, options): + if self.max_form_memory_size is not None and \ + content_length is not None and \ + content_length > self.max_form_memory_size: + raise exceptions.RequestEntityTooLarge() + form = url_decode_stream(stream, self.charset, + errors=self.errors, cls=self.cls) + return stream, form, self.cls() + + #: mapping of mimetypes to parsing functions + parse_functions = { + 'multipart/form-data': _parse_multipart, + 'application/x-www-form-urlencoded': _parse_urlencoded, + 'application/x-url-encoded': _parse_urlencoded + } + + +def is_valid_multipart_boundary(boundary): + """Checks if the string given is a valid multipart boundary.""" + return _multipart_boundary_re.match(boundary) is not None + + +def _line_parse(line): + """Removes line ending characters and returns a tuple (`stripped_line`, + `is_terminated`). + """ + if line[-2:] in ['\r\n', b'\r\n']: + return line[:-2], True + elif line[-1:] in ['\r', '\n', b'\r', b'\n']: + return line[:-1], True + return line, False + + +def parse_multipart_headers(iterable): + """Parses multipart headers from an iterable that yields lines (including + the trailing newline symbol). The iterable has to be newline terminated. + + The iterable will stop at the line where the headers ended so it can be + further consumed. + + :param iterable: iterable of strings that are newline terminated + """ + result = [] + for line in iterable: + line = to_native(line) + line, line_terminated = _line_parse(line) + if not line_terminated: + raise ValueError('unexpected end of line in multipart header') + if not line: + break + elif line[0] in ' \t' and result: + key, value = result[-1] + result[-1] = (key, value + '\n ' + line[1:]) + else: + parts = line.split(':', 1) + if len(parts) == 2: + result.append((parts[0].strip(), parts[1].strip())) + + # we link the list to the headers, no need to create a copy, the + # list was not shared anyways. + return Headers(result) + + +_begin_form = 'begin_form' +_begin_file = 'begin_file' +_cont = 'cont' +_end = 'end' + + +class MultiPartParser(object): + + def __init__(self, stream_factory=None, charset='utf-8', errors='replace', + max_form_memory_size=None, cls=None, buffer_size=64 * 1024): + self.charset = charset + self.errors = errors + self.max_form_memory_size = max_form_memory_size + self.stream_factory = default_stream_factory if stream_factory is None else stream_factory + self.cls = MultiDict if cls is None else cls + + # make sure the buffer size is divisible by four so that we can base64 + # decode chunk by chunk + assert buffer_size % 4 == 0, 'buffer size has to be divisible by 4' + # also the buffer size has to be at least 1024 bytes long or long headers + # will freak out the system + assert buffer_size >= 1024, 'buffer size has to be at least 1KB' + + self.buffer_size = buffer_size + + def _fix_ie_filename(self, filename): + """Internet Explorer 6 transmits the full file name if a file is + uploaded. This function strips the full path if it thinks the + filename is Windows-like absolute. + """ + if filename[1:3] == ':\\' or filename[:2] == '\\\\': + return filename.split('\\')[-1] + return filename + + def _find_terminator(self, iterator): + """The terminator might have some additional newlines before it. + There is at least one application that sends additional newlines + before headers (the python setuptools package). + """ + for line in iterator: + if not line: + break + line = line.strip() + if line: + return line + return b'' + + def fail(self, message): + raise ValueError(message) + + def get_part_encoding(self, headers): + transfer_encoding = headers.get('content-transfer-encoding') + if transfer_encoding is not None and \ + transfer_encoding in _supported_multipart_encodings: + return transfer_encoding + + def get_part_charset(self, headers): + # Figure out input charset for current part + content_type = headers.get('content-type') + if content_type: + mimetype, ct_params = parse_options_header(content_type) + return ct_params.get('charset', self.charset) + return self.charset + + def start_file_streaming(self, filename, headers, total_content_length): + if isinstance(filename, bytes): + filename = filename.decode(self.charset, self.errors) + filename = self._fix_ie_filename(filename) + content_type = headers.get('content-type') + try: + content_length = int(headers['content-length']) + except (KeyError, ValueError): + content_length = 0 + container = self.stream_factory(total_content_length, content_type, + filename, content_length) + return filename, container + + def in_memory_threshold_reached(self, bytes): + raise exceptions.RequestEntityTooLarge() + + def validate_boundary(self, boundary): + if not boundary: + self.fail('Missing boundary') + if not is_valid_multipart_boundary(boundary): + self.fail('Invalid boundary: %s' % boundary) + if len(boundary) > self.buffer_size: # pragma: no cover + # this should never happen because we check for a minimum size + # of 1024 and boundaries may not be longer than 200. The only + # situation when this happens is for non debug builds where + # the assert is skipped. + self.fail('Boundary longer than buffer size') + + def parse_lines(self, file, boundary, content_length, cap_at_buffer=True): + """Generate parts of + ``('begin_form', (headers, name))`` + ``('begin_file', (headers, name, filename))`` + ``('cont', bytestring)`` + ``('end', None)`` + + Always obeys the grammar + parts = ( begin_form cont* end | + begin_file cont* end )* + """ + next_part = b'--' + boundary + last_part = next_part + b'--' + + iterator = chain(make_line_iter(file, limit=content_length, + buffer_size=self.buffer_size, + cap_at_buffer=cap_at_buffer), + _empty_string_iter) + + terminator = self._find_terminator(iterator) + + if terminator == last_part: + return + elif terminator != next_part: + self.fail('Expected boundary at start of multipart data') + + while terminator != last_part: + headers = parse_multipart_headers(iterator) + + disposition = headers.get('content-disposition') + if disposition is None: + self.fail('Missing Content-Disposition header') + disposition, extra = parse_options_header(disposition) + transfer_encoding = self.get_part_encoding(headers) + name = extra.get('name') + + # Accept filename* to support non-ascii filenames as per rfc2231 + filename = extra.get('filename') or extra.get('filename*') + + # if no content type is given we stream into memory. A list is + # used as a temporary container. + if filename is None: + yield _begin_form, (headers, name) + + # otherwise we parse the rest of the headers and ask the stream + # factory for something we can write in. + else: + yield _begin_file, (headers, name, filename) + + buf = b'' + for line in iterator: + if not line: + self.fail('unexpected end of stream') + + if line[:2] == b'--': + terminator = line.rstrip() + if terminator in (next_part, last_part): + break + + if transfer_encoding is not None: + if transfer_encoding == 'base64': + transfer_encoding = 'base64_codec' + try: + line = codecs.decode(line, transfer_encoding) + except Exception: + self.fail('could not decode transfer encoded chunk') + + # we have something in the buffer from the last iteration. + # this is usually a newline delimiter. + if buf: + yield _cont, buf + buf = b'' + + # If the line ends with windows CRLF we write everything except + # the last two bytes. In all other cases however we write + # everything except the last byte. If it was a newline, that's + # fine, otherwise it does not matter because we will write it + # the next iteration. this ensures we do not write the + # final newline into the stream. That way we do not have to + # truncate the stream. However we do have to make sure that + # if something else than a newline is in there we write it + # out. + if line[-2:] == b'\r\n': + buf = b'\r\n' + cutoff = -2 + else: + buf = line[-1:] + cutoff = -1 + yield _cont, line[:cutoff] + + else: # pragma: no cover + raise ValueError('unexpected end of part') + + # if we have a leftover in the buffer that is not a newline + # character we have to flush it, otherwise we will chop of + # certain values. + if buf not in (b'', b'\r', b'\n', b'\r\n'): + yield _cont, buf + + yield _end, None + + def parse_parts(self, file, boundary, content_length): + """Generate ``('file', (name, val))`` and + ``('form', (name, val))`` parts. + """ + in_memory = 0 + + for ellt, ell in self.parse_lines(file, boundary, content_length): + if ellt == _begin_file: + headers, name, filename = ell + is_file = True + guard_memory = False + filename, container = self.start_file_streaming( + filename, headers, content_length) + _write = container.write + + elif ellt == _begin_form: + headers, name = ell + is_file = False + container = [] + _write = container.append + guard_memory = self.max_form_memory_size is not None + + elif ellt == _cont: + _write(ell) + # if we write into memory and there is a memory size limit we + # count the number of bytes in memory and raise an exception if + # there is too much data in memory. + if guard_memory: + in_memory += len(ell) + if in_memory > self.max_form_memory_size: + self.in_memory_threshold_reached(in_memory) + + elif ellt == _end: + if is_file: + container.seek(0) + yield ('file', + (name, FileStorage(container, filename, name, + headers=headers))) + else: + part_charset = self.get_part_charset(headers) + yield ('form', + (name, b''.join(container).decode( + part_charset, self.errors))) + + def parse(self, file, boundary, content_length): + formstream, filestream = tee( + self.parse_parts(file, boundary, content_length), 2) + form = (p[1] for p in formstream if p[0] == 'form') + files = (p[1] for p in filestream if p[0] == 'file') + return self.cls(form), self.cls(files) + + +from werkzeug import exceptions diff --git a/pyextra/werkzeug/http.py b/pyextra/werkzeug/http.py new file mode 100644 index 00000000000000..22197221c8fa3b --- /dev/null +++ b/pyextra/werkzeug/http.py @@ -0,0 +1,1158 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.http + ~~~~~~~~~~~~~ + + Werkzeug comes with a bunch of utilities that help Werkzeug to deal with + HTTP data. Most of the classes and functions provided by this module are + used by the wrappers, but they are useful on their own, too, especially if + the response and request objects are not used. + + This covers some of the more HTTP centric features of WSGI, some other + utilities such as cookie handling are documented in the `werkzeug.utils` + module. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re +import warnings +from time import time, gmtime +try: + from email.utils import parsedate_tz +except ImportError: # pragma: no cover + from email.Utils import parsedate_tz +try: + from urllib.request import parse_http_list as _parse_list_header + from urllib.parse import unquote_to_bytes as _unquote +except ImportError: # pragma: no cover + from urllib2 import parse_http_list as _parse_list_header, \ + unquote as _unquote +from datetime import datetime, timedelta +from hashlib import md5 +import base64 + +from werkzeug._internal import _cookie_quote, _make_cookie_domain, \ + _cookie_parse_impl +from werkzeug._compat import to_unicode, iteritems, text_type, \ + string_types, try_coerce_native, to_bytes, PY2, \ + integer_types + + +_cookie_charset = 'latin1' +# for explanation of "media-range", etc. see Sections 5.3.{1,2} of RFC 7231 +_accept_re = re.compile( + r'''( # media-range capturing-parenthesis + [^\s;,]+ # type/subtype + (?:[ \t]*;[ \t]* # ";" + (?: # parameter non-capturing-parenthesis + [^\s;,q][^\s;,]* # token that doesn't start with "q" + | # or + q[^\s;,=][^\s;,]* # token that is more than just "q" + ) + )* # zero or more parameters + ) # end of media-range + (?:[ \t]*;[ \t]*q= # weight is a "q" parameter + (\d*(?:\.\d+)?) # qvalue capturing-parentheses + [^,]* # "extension" accept params: who cares? + )? # accept params are optional + ''', re.VERBOSE) +_token_chars = frozenset("!#$%&'*+-.0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ" + '^_`abcdefghijklmnopqrstuvwxyz|~') +_etag_re = re.compile(r'([Ww]/)?(?:"(.*?)"|(.*?))(?:\s*,\s*|$)') +_unsafe_header_chars = set('()<>@,;:\"/[]?={} \t') +_option_header_piece_re = re.compile(r''' + ;\s* + (?P + "[^"\\]*(?:\\.[^"\\]*)*" # quoted string + | + [^\s;,=*]+ # token + ) + \s* + (?: # optionally followed by =value + (?: # equals sign, possibly with encoding + \*\s*=\s* # * indicates extended notation + (?P[^\s]+?) + '(?P[^\s]*?)' + | + =\s* # basic notation + ) + (?P + "[^"\\]*(?:\\.[^"\\]*)*" # quoted string + | + [^;,]+ # token + )? + )? + \s* +''', flags=re.VERBOSE) +_option_header_start_mime_type = re.compile(r',\s*([^;,\s]+)([;,]\s*.+)?') + +_entity_headers = frozenset([ + 'allow', 'content-encoding', 'content-language', 'content-length', + 'content-location', 'content-md5', 'content-range', 'content-type', + 'expires', 'last-modified' +]) +_hop_by_hop_headers = frozenset([ + 'connection', 'keep-alive', 'proxy-authenticate', + 'proxy-authorization', 'te', 'trailer', 'transfer-encoding', + 'upgrade' +]) + + +HTTP_STATUS_CODES = { + 100: 'Continue', + 101: 'Switching Protocols', + 102: 'Processing', + 200: 'OK', + 201: 'Created', + 202: 'Accepted', + 203: 'Non Authoritative Information', + 204: 'No Content', + 205: 'Reset Content', + 206: 'Partial Content', + 207: 'Multi Status', + 226: 'IM Used', # see RFC 3229 + 300: 'Multiple Choices', + 301: 'Moved Permanently', + 302: 'Found', + 303: 'See Other', + 304: 'Not Modified', + 305: 'Use Proxy', + 307: 'Temporary Redirect', + 400: 'Bad Request', + 401: 'Unauthorized', + 402: 'Payment Required', # unused + 403: 'Forbidden', + 404: 'Not Found', + 405: 'Method Not Allowed', + 406: 'Not Acceptable', + 407: 'Proxy Authentication Required', + 408: 'Request Timeout', + 409: 'Conflict', + 410: 'Gone', + 411: 'Length Required', + 412: 'Precondition Failed', + 413: 'Request Entity Too Large', + 414: 'Request URI Too Long', + 415: 'Unsupported Media Type', + 416: 'Requested Range Not Satisfiable', + 417: 'Expectation Failed', + 418: 'I\'m a teapot', # see RFC 2324 + 422: 'Unprocessable Entity', + 423: 'Locked', + 424: 'Failed Dependency', + 426: 'Upgrade Required', + 428: 'Precondition Required', # see RFC 6585 + 429: 'Too Many Requests', + 431: 'Request Header Fields Too Large', + 449: 'Retry With', # proprietary MS extension + 451: 'Unavailable For Legal Reasons', + 500: 'Internal Server Error', + 501: 'Not Implemented', + 502: 'Bad Gateway', + 503: 'Service Unavailable', + 504: 'Gateway Timeout', + 505: 'HTTP Version Not Supported', + 507: 'Insufficient Storage', + 510: 'Not Extended' +} + + +def wsgi_to_bytes(data): + """coerce wsgi unicode represented bytes to real ones + + """ + if isinstance(data, bytes): + return data + return data.encode('latin1') # XXX: utf8 fallback? + + +def bytes_to_wsgi(data): + assert isinstance(data, bytes), 'data must be bytes' + if isinstance(data, str): + return data + else: + return data.decode('latin1') + + +def quote_header_value(value, extra_chars='', allow_token=True): + """Quote a header value if necessary. + + .. versionadded:: 0.5 + + :param value: the value to quote. + :param extra_chars: a list of extra characters to skip quoting. + :param allow_token: if this is enabled token values are returned + unchanged. + """ + if isinstance(value, bytes): + value = bytes_to_wsgi(value) + value = str(value) + if allow_token: + token_chars = _token_chars | set(extra_chars) + if set(value).issubset(token_chars): + return value + return '"%s"' % value.replace('\\', '\\\\').replace('"', '\\"') + + +def unquote_header_value(value, is_filename=False): + r"""Unquotes a header value. (Reversal of :func:`quote_header_value`). + This does not use the real unquoting but what browsers are actually + using for quoting. + + .. versionadded:: 0.5 + + :param value: the header value to unquote. + """ + if value and value[0] == value[-1] == '"': + # this is not the real unquoting, but fixing this so that the + # RFC is met will result in bugs with internet explorer and + # probably some other browsers as well. IE for example is + # uploading files with "C:\foo\bar.txt" as filename + value = value[1:-1] + + # if this is a filename and the starting characters look like + # a UNC path, then just return the value without quotes. Using the + # replace sequence below on a UNC path has the effect of turning + # the leading double slash into a single slash and then + # _fix_ie_filename() doesn't work correctly. See #458. + if not is_filename or value[:2] != '\\\\': + return value.replace('\\\\', '\\').replace('\\"', '"') + return value + + +def dump_options_header(header, options): + """The reverse function to :func:`parse_options_header`. + + :param header: the header to dump + :param options: a dict of options to append. + """ + segments = [] + if header is not None: + segments.append(header) + for key, value in iteritems(options): + if value is None: + segments.append(key) + else: + segments.append('%s=%s' % (key, quote_header_value(value))) + return '; '.join(segments) + + +def dump_header(iterable, allow_token=True): + """Dump an HTTP header again. This is the reversal of + :func:`parse_list_header`, :func:`parse_set_header` and + :func:`parse_dict_header`. This also quotes strings that include an + equals sign unless you pass it as dict of key, value pairs. + + >>> dump_header({'foo': 'bar baz'}) + 'foo="bar baz"' + >>> dump_header(('foo', 'bar baz')) + 'foo, "bar baz"' + + :param iterable: the iterable or dict of values to quote. + :param allow_token: if set to `False` tokens as values are disallowed. + See :func:`quote_header_value` for more details. + """ + if isinstance(iterable, dict): + items = [] + for key, value in iteritems(iterable): + if value is None: + items.append(key) + else: + items.append('%s=%s' % ( + key, + quote_header_value(value, allow_token=allow_token) + )) + else: + items = [quote_header_value(x, allow_token=allow_token) + for x in iterable] + return ', '.join(items) + + +def parse_list_header(value): + """Parse lists as described by RFC 2068 Section 2. + + In particular, parse comma-separated lists where the elements of + the list may include quoted-strings. A quoted-string could + contain a comma. A non-quoted string could have quotes in the + middle. Quotes are removed automatically after parsing. + + It basically works like :func:`parse_set_header` just that items + may appear multiple times and case sensitivity is preserved. + + The return value is a standard :class:`list`: + + >>> parse_list_header('token, "quoted value"') + ['token', 'quoted value'] + + To create a header from the :class:`list` again, use the + :func:`dump_header` function. + + :param value: a string with a list header. + :return: :class:`list` + """ + result = [] + for item in _parse_list_header(value): + if item[:1] == item[-1:] == '"': + item = unquote_header_value(item[1:-1]) + result.append(item) + return result + + +def parse_dict_header(value, cls=dict): + """Parse lists of key, value pairs as described by RFC 2068 Section 2 and + convert them into a python dict (or any other mapping object created from + the type with a dict like interface provided by the `cls` argument): + + >>> d = parse_dict_header('foo="is a fish", bar="as well"') + >>> type(d) is dict + True + >>> sorted(d.items()) + [('bar', 'as well'), ('foo', 'is a fish')] + + If there is no value for a key it will be `None`: + + >>> parse_dict_header('key_without_value') + {'key_without_value': None} + + To create a header from the :class:`dict` again, use the + :func:`dump_header` function. + + .. versionchanged:: 0.9 + Added support for `cls` argument. + + :param value: a string with a dict header. + :param cls: callable to use for storage of parsed results. + :return: an instance of `cls` + """ + result = cls() + if not isinstance(value, text_type): + # XXX: validate + value = bytes_to_wsgi(value) + for item in _parse_list_header(value): + if '=' not in item: + result[item] = None + continue + name, value = item.split('=', 1) + if value[:1] == value[-1:] == '"': + value = unquote_header_value(value[1:-1]) + result[name] = value + return result + + +def parse_options_header(value, multiple=False): + """Parse a ``Content-Type`` like header into a tuple with the content + type and the options: + + >>> parse_options_header('text/html; charset=utf8') + ('text/html', {'charset': 'utf8'}) + + This should not be used to parse ``Cache-Control`` like headers that use + a slightly different format. For these headers use the + :func:`parse_dict_header` function. + + .. versionadded:: 0.5 + + :param value: the header to parse. + :param multiple: Whether try to parse and return multiple MIME types + :return: (mimetype, options) or (mimetype, options, mimetype, options, …) + if multiple=True + """ + if not value: + return '', {} + + result = [] + + value = "," + value.replace("\n", ",") + while value: + match = _option_header_start_mime_type.match(value) + if not match: + break + result.append(match.group(1)) # mimetype + options = {} + # Parse options + rest = match.group(2) + while rest: + optmatch = _option_header_piece_re.match(rest) + if not optmatch: + break + option, encoding, _, option_value = optmatch.groups() + option = unquote_header_value(option) + if option_value is not None: + option_value = unquote_header_value( + option_value, + option == 'filename') + if encoding is not None: + option_value = _unquote(option_value).decode(encoding) + options[option] = option_value + rest = rest[optmatch.end():] + result.append(options) + if multiple is False: + return tuple(result) + value = rest + + return tuple(result) if result else ('', {}) + + +def parse_accept_header(value, cls=None): + """Parses an HTTP Accept-* header. This does not implement a complete + valid algorithm but one that supports at least value and quality + extraction. + + Returns a new :class:`Accept` object (basically a list of ``(value, quality)`` + tuples sorted by the quality with some additional accessor methods). + + The second parameter can be a subclass of :class:`Accept` that is created + with the parsed values and returned. + + :param value: the accept header string to be parsed. + :param cls: the wrapper class for the return value (can be + :class:`Accept` or a subclass thereof) + :return: an instance of `cls`. + """ + if cls is None: + cls = Accept + + if not value: + return cls(None) + + result = [] + for match in _accept_re.finditer(value): + quality = match.group(2) + if not quality: + quality = 1 + else: + quality = max(min(float(quality), 1), 0) + result.append((match.group(1), quality)) + return cls(result) + + +def parse_cache_control_header(value, on_update=None, cls=None): + """Parse a cache control header. The RFC differs between response and + request cache control, this method does not. It's your responsibility + to not use the wrong control statements. + + .. versionadded:: 0.5 + The `cls` was added. If not specified an immutable + :class:`~werkzeug.datastructures.RequestCacheControl` is returned. + + :param value: a cache control header to be parsed. + :param on_update: an optional callable that is called every time a value + on the :class:`~werkzeug.datastructures.CacheControl` + object is changed. + :param cls: the class for the returned object. By default + :class:`~werkzeug.datastructures.RequestCacheControl` is used. + :return: a `cls` object. + """ + if cls is None: + cls = RequestCacheControl + if not value: + return cls(None, on_update) + return cls(parse_dict_header(value), on_update) + + +def parse_set_header(value, on_update=None): + """Parse a set-like header and return a + :class:`~werkzeug.datastructures.HeaderSet` object: + + >>> hs = parse_set_header('token, "quoted value"') + + The return value is an object that treats the items case-insensitively + and keeps the order of the items: + + >>> 'TOKEN' in hs + True + >>> hs.index('quoted value') + 1 + >>> hs + HeaderSet(['token', 'quoted value']) + + To create a header from the :class:`HeaderSet` again, use the + :func:`dump_header` function. + + :param value: a set header to be parsed. + :param on_update: an optional callable that is called every time a + value on the :class:`~werkzeug.datastructures.HeaderSet` + object is changed. + :return: a :class:`~werkzeug.datastructures.HeaderSet` + """ + if not value: + return HeaderSet(None, on_update) + return HeaderSet(parse_list_header(value), on_update) + + +def parse_authorization_header(value): + """Parse an HTTP basic/digest authorization header transmitted by the web + browser. The return value is either `None` if the header was invalid or + not given, otherwise an :class:`~werkzeug.datastructures.Authorization` + object. + + :param value: the authorization header to parse. + :return: a :class:`~werkzeug.datastructures.Authorization` object or `None`. + """ + if not value: + return + value = wsgi_to_bytes(value) + try: + auth_type, auth_info = value.split(None, 1) + auth_type = auth_type.lower() + except ValueError: + return + if auth_type == b'basic': + try: + username, password = base64.b64decode(auth_info).split(b':', 1) + except Exception: + return + return Authorization('basic', {'username': bytes_to_wsgi(username), + 'password': bytes_to_wsgi(password)}) + elif auth_type == b'digest': + auth_map = parse_dict_header(auth_info) + for key in 'username', 'realm', 'nonce', 'uri', 'response': + if key not in auth_map: + return + if 'qop' in auth_map: + if not auth_map.get('nc') or not auth_map.get('cnonce'): + return + return Authorization('digest', auth_map) + + +def parse_www_authenticate_header(value, on_update=None): + """Parse an HTTP WWW-Authenticate header into a + :class:`~werkzeug.datastructures.WWWAuthenticate` object. + + :param value: a WWW-Authenticate header to parse. + :param on_update: an optional callable that is called every time a value + on the :class:`~werkzeug.datastructures.WWWAuthenticate` + object is changed. + :return: a :class:`~werkzeug.datastructures.WWWAuthenticate` object. + """ + if not value: + return WWWAuthenticate(on_update=on_update) + try: + auth_type, auth_info = value.split(None, 1) + auth_type = auth_type.lower() + except (ValueError, AttributeError): + return WWWAuthenticate(value.strip().lower(), on_update=on_update) + return WWWAuthenticate(auth_type, parse_dict_header(auth_info), + on_update) + + +def parse_if_range_header(value): + """Parses an if-range header which can be an etag or a date. Returns + a :class:`~werkzeug.datastructures.IfRange` object. + + .. versionadded:: 0.7 + """ + if not value: + return IfRange() + date = parse_date(value) + if date is not None: + return IfRange(date=date) + # drop weakness information + return IfRange(unquote_etag(value)[0]) + + +def parse_range_header(value, make_inclusive=True): + """Parses a range header into a :class:`~werkzeug.datastructures.Range` + object. If the header is missing or malformed `None` is returned. + `ranges` is a list of ``(start, stop)`` tuples where the ranges are + non-inclusive. + + .. versionadded:: 0.7 + """ + if not value or '=' not in value: + return None + + ranges = [] + last_end = 0 + units, rng = value.split('=', 1) + units = units.strip().lower() + + for item in rng.split(','): + item = item.strip() + if '-' not in item: + return None + if item.startswith('-'): + if last_end < 0: + return None + try: + begin = int(item) + except ValueError: + return None + end = None + last_end = -1 + elif '-' in item: + begin, end = item.split('-', 1) + begin = begin.strip() + end = end.strip() + if not begin.isdigit(): + return None + begin = int(begin) + if begin < last_end or last_end < 0: + return None + if end: + if not end.isdigit(): + return None + end = int(end) + 1 + if begin >= end: + return None + else: + end = None + last_end = end + ranges.append((begin, end)) + + return Range(units, ranges) + + +def parse_content_range_header(value, on_update=None): + """Parses a range header into a + :class:`~werkzeug.datastructures.ContentRange` object or `None` if + parsing is not possible. + + .. versionadded:: 0.7 + + :param value: a content range header to be parsed. + :param on_update: an optional callable that is called every time a value + on the :class:`~werkzeug.datastructures.ContentRange` + object is changed. + """ + if value is None: + return None + try: + units, rangedef = (value or '').strip().split(None, 1) + except ValueError: + return None + + if '/' not in rangedef: + return None + rng, length = rangedef.split('/', 1) + if length == '*': + length = None + elif length.isdigit(): + length = int(length) + else: + return None + + if rng == '*': + return ContentRange(units, None, None, length, on_update=on_update) + elif '-' not in rng: + return None + + start, stop = rng.split('-', 1) + try: + start = int(start) + stop = int(stop) + 1 + except ValueError: + return None + + if is_byte_range_valid(start, stop, length): + return ContentRange(units, start, stop, length, on_update=on_update) + + +def quote_etag(etag, weak=False): + """Quote an etag. + + :param etag: the etag to quote. + :param weak: set to `True` to tag it "weak". + """ + if '"' in etag: + raise ValueError('invalid etag') + etag = '"%s"' % etag + if weak: + etag = 'W/' + etag + return etag + + +def unquote_etag(etag): + """Unquote a single etag: + + >>> unquote_etag('W/"bar"') + ('bar', True) + >>> unquote_etag('"bar"') + ('bar', False) + + :param etag: the etag identifier to unquote. + :return: a ``(etag, weak)`` tuple. + """ + if not etag: + return None, None + etag = etag.strip() + weak = False + if etag.startswith(('W/', 'w/')): + weak = True + etag = etag[2:] + if etag[:1] == etag[-1:] == '"': + etag = etag[1:-1] + return etag, weak + + +def parse_etags(value): + """Parse an etag header. + + :param value: the tag header to parse + :return: an :class:`~werkzeug.datastructures.ETags` object. + """ + if not value: + return ETags() + strong = [] + weak = [] + end = len(value) + pos = 0 + while pos < end: + match = _etag_re.match(value, pos) + if match is None: + break + is_weak, quoted, raw = match.groups() + if raw == '*': + return ETags(star_tag=True) + elif quoted: + raw = quoted + if is_weak: + weak.append(raw) + else: + strong.append(raw) + pos = match.end() + return ETags(strong, weak) + + +def generate_etag(data): + """Generate an etag for some data.""" + return md5(data).hexdigest() + + +def parse_date(value): + """Parse one of the following date formats into a datetime object: + + .. sourcecode:: text + + Sun, 06 Nov 1994 08:49:37 GMT ; RFC 822, updated by RFC 1123 + Sunday, 06-Nov-94 08:49:37 GMT ; RFC 850, obsoleted by RFC 1036 + Sun Nov 6 08:49:37 1994 ; ANSI C's asctime() format + + If parsing fails the return value is `None`. + + :param value: a string with a supported date format. + :return: a :class:`datetime.datetime` object. + """ + if value: + t = parsedate_tz(value.strip()) + if t is not None: + try: + year = t[0] + # unfortunately that function does not tell us if two digit + # years were part of the string, or if they were prefixed + # with two zeroes. So what we do is to assume that 69-99 + # refer to 1900, and everything below to 2000 + if year >= 0 and year <= 68: + year += 2000 + elif year >= 69 and year <= 99: + year += 1900 + return datetime(*((year,) + t[1:7])) - \ + timedelta(seconds=t[-1] or 0) + except (ValueError, OverflowError): + return None + + +def _dump_date(d, delim): + """Used for `http_date` and `cookie_date`.""" + if d is None: + d = gmtime() + elif isinstance(d, datetime): + d = d.utctimetuple() + elif isinstance(d, (integer_types, float)): + d = gmtime(d) + return '%s, %02d%s%s%s%s %02d:%02d:%02d GMT' % ( + ('Mon', 'Tue', 'Wed', 'Thu', 'Fri', 'Sat', 'Sun')[d.tm_wday], + d.tm_mday, delim, + ('Jan', 'Feb', 'Mar', 'Apr', 'May', 'Jun', 'Jul', 'Aug', 'Sep', + 'Oct', 'Nov', 'Dec')[d.tm_mon - 1], + delim, str(d.tm_year), d.tm_hour, d.tm_min, d.tm_sec + ) + + +def cookie_date(expires=None): + """Formats the time to ensure compatibility with Netscape's cookie + standard. + + Accepts a floating point number expressed in seconds since the epoch in, a + datetime object or a timetuple. All times in UTC. The :func:`parse_date` + function can be used to parse such a date. + + Outputs a string in the format ``Wdy, DD-Mon-YYYY HH:MM:SS GMT``. + + :param expires: If provided that date is used, otherwise the current. + """ + return _dump_date(expires, '-') + + +def http_date(timestamp=None): + """Formats the time to match the RFC1123 date format. + + Accepts a floating point number expressed in seconds since the epoch in, a + datetime object or a timetuple. All times in UTC. The :func:`parse_date` + function can be used to parse such a date. + + Outputs a string in the format ``Wdy, DD Mon YYYY HH:MM:SS GMT``. + + :param timestamp: If provided that date is used, otherwise the current. + """ + return _dump_date(timestamp, ' ') + + +def parse_age(value=None): + """Parses a base-10 integer count of seconds into a timedelta. + + If parsing fails, the return value is `None`. + + :param value: a string consisting of an integer represented in base-10 + :return: a :class:`datetime.timedelta` object or `None`. + """ + if not value: + return None + try: + seconds = int(value) + except ValueError: + return None + if seconds < 0: + return None + try: + return timedelta(seconds=seconds) + except OverflowError: + return None + + +def dump_age(age=None): + """Formats the duration as a base-10 integer. + + :param age: should be an integer number of seconds, + a :class:`datetime.timedelta` object, or, + if the age is unknown, `None` (default). + """ + if age is None: + return + if isinstance(age, timedelta): + # do the equivalent of Python 2.7's timedelta.total_seconds(), + # but disregarding fractional seconds + age = age.seconds + (age.days * 24 * 3600) + + age = int(age) + if age < 0: + raise ValueError('age cannot be negative') + + return str(age) + + +def is_resource_modified(environ, etag=None, data=None, last_modified=None, + ignore_if_range=True): + """Convenience method for conditional requests. + + :param environ: the WSGI environment of the request to be checked. + :param etag: the etag for the response for comparison. + :param data: or alternatively the data of the response to automatically + generate an etag using :func:`generate_etag`. + :param last_modified: an optional date of the last modification. + :param ignore_if_range: If `False`, `If-Range` header will be taken into + account. + :return: `True` if the resource was modified, otherwise `False`. + """ + if etag is None and data is not None: + etag = generate_etag(data) + elif data is not None: + raise TypeError('both data and etag given') + if environ['REQUEST_METHOD'] not in ('GET', 'HEAD'): + return False + + unmodified = False + if isinstance(last_modified, string_types): + last_modified = parse_date(last_modified) + + # ensure that microsecond is zero because the HTTP spec does not transmit + # that either and we might have some false positives. See issue #39 + if last_modified is not None: + last_modified = last_modified.replace(microsecond=0) + + if_range = None + if not ignore_if_range and 'HTTP_RANGE' in environ: + # http://tools.ietf.org/html/rfc7233#section-3.2 + # A server MUST ignore an If-Range header field received in a request + # that does not contain a Range header field. + if_range = parse_if_range_header(environ.get('HTTP_IF_RANGE')) + + if if_range is not None and if_range.date is not None: + modified_since = if_range.date + else: + modified_since = parse_date(environ.get('HTTP_IF_MODIFIED_SINCE')) + + if modified_since and last_modified and last_modified <= modified_since: + unmodified = True + + if etag: + etag, _ = unquote_etag(etag) + if if_range is not None and if_range.etag is not None: + unmodified = parse_etags(if_range.etag).contains(etag) + else: + if_none_match = parse_etags(environ.get('HTTP_IF_NONE_MATCH')) + if if_none_match: + # http://tools.ietf.org/html/rfc7232#section-3.2 + # "A recipient MUST use the weak comparison function when comparing + # entity-tags for If-None-Match" + unmodified = if_none_match.contains_weak(etag) + + # https://tools.ietf.org/html/rfc7232#section-3.1 + # "Origin server MUST use the strong comparison function when + # comparing entity-tags for If-Match" + if_match = parse_etags(environ.get('HTTP_IF_MATCH')) + if if_match: + unmodified = not if_match.is_strong(etag) + + return not unmodified + + +def remove_entity_headers(headers, allowed=('expires', 'content-location')): + """Remove all entity headers from a list or :class:`Headers` object. This + operation works in-place. `Expires` and `Content-Location` headers are + by default not removed. The reason for this is :rfc:`2616` section + 10.3.5 which specifies some entity headers that should be sent. + + .. versionchanged:: 0.5 + added `allowed` parameter. + + :param headers: a list or :class:`Headers` object. + :param allowed: a list of headers that should still be allowed even though + they are entity headers. + """ + allowed = set(x.lower() for x in allowed) + headers[:] = [(key, value) for key, value in headers if + not is_entity_header(key) or key.lower() in allowed] + + +def remove_hop_by_hop_headers(headers): + """Remove all HTTP/1.1 "Hop-by-Hop" headers from a list or + :class:`Headers` object. This operation works in-place. + + .. versionadded:: 0.5 + + :param headers: a list or :class:`Headers` object. + """ + headers[:] = [(key, value) for key, value in headers if + not is_hop_by_hop_header(key)] + + +def is_entity_header(header): + """Check if a header is an entity header. + + .. versionadded:: 0.5 + + :param header: the header to test. + :return: `True` if it's an entity header, `False` otherwise. + """ + return header.lower() in _entity_headers + + +def is_hop_by_hop_header(header): + """Check if a header is an HTTP/1.1 "Hop-by-Hop" header. + + .. versionadded:: 0.5 + + :param header: the header to test. + :return: `True` if it's an HTTP/1.1 "Hop-by-Hop" header, `False` otherwise. + """ + return header.lower() in _hop_by_hop_headers + + +def parse_cookie(header, charset='utf-8', errors='replace', cls=None): + """Parse a cookie. Either from a string or WSGI environ. + + Per default encoding errors are ignored. If you want a different behavior + you can set `errors` to ``'replace'`` or ``'strict'``. In strict mode a + :exc:`HTTPUnicodeError` is raised. + + .. versionchanged:: 0.5 + This function now returns a :class:`TypeConversionDict` instead of a + regular dict. The `cls` parameter was added. + + :param header: the header to be used to parse the cookie. Alternatively + this can be a WSGI environment. + :param charset: the charset for the cookie values. + :param errors: the error behavior for the charset decoding. + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`TypeConversionDict` is + used. + """ + if isinstance(header, dict): + header = header.get('HTTP_COOKIE', '') + elif header is None: + header = '' + + # If the value is an unicode string it's mangled through latin1. This + # is done because on PEP 3333 on Python 3 all headers are assumed latin1 + # which however is incorrect for cookies, which are sent in page encoding. + # As a result we + if isinstance(header, text_type): + header = header.encode('latin1', 'replace') + + if cls is None: + cls = TypeConversionDict + + def _parse_pairs(): + for key, val in _cookie_parse_impl(header): + key = to_unicode(key, charset, errors, allow_none_charset=True) + val = to_unicode(val, charset, errors, allow_none_charset=True) + yield try_coerce_native(key), val + + return cls(_parse_pairs()) + + +def dump_cookie(key, value='', max_age=None, expires=None, path='/', + domain=None, secure=False, httponly=False, + charset='utf-8', sync_expires=True, max_size=4093, + samesite=None): + """Creates a new Set-Cookie header without the ``Set-Cookie`` prefix + The parameters are the same as in the cookie Morsel object in the + Python standard library but it accepts unicode data, too. + + On Python 3 the return value of this function will be a unicode + string, on Python 2 it will be a native string. In both cases the + return value is usually restricted to ascii as the vast majority of + values are properly escaped, but that is no guarantee. If a unicode + string is returned it's tunneled through latin1 as required by + PEP 3333. + + The return value is not ASCII safe if the key contains unicode + characters. This is technically against the specification but + happens in the wild. It's strongly recommended to not use + non-ASCII values for the keys. + + :param max_age: should be a number of seconds, or `None` (default) if + the cookie should last only as long as the client's + browser session. Additionally `timedelta` objects + are accepted, too. + :param expires: should be a `datetime` object or unix timestamp. + :param path: limits the cookie to a given path, per default it will + span the whole domain. + :param domain: Use this if you want to set a cross-domain cookie. For + example, ``domain=".example.com"`` will set a cookie + that is readable by the domain ``www.example.com``, + ``foo.example.com`` etc. Otherwise, a cookie will only + be readable by the domain that set it. + :param secure: The cookie will only be available via HTTPS + :param httponly: disallow JavaScript to access the cookie. This is an + extension to the cookie standard and probably not + supported by all browsers. + :param charset: the encoding for unicode values. + :param sync_expires: automatically set expires if max_age is defined + but expires not. + :param max_size: Warn if the final header value exceeds this size. The + default, 4093, should be safely `supported by most browsers + `_. Set to 0 to disable this check. + :param samesite: Limits the scope of the cookie such that it will only + be attached to requests if those requests are "same-site". + + .. _`cookie`: http://browsercookielimits.squawky.net/ + """ + key = to_bytes(key, charset) + value = to_bytes(value, charset) + + if path is not None: + path = iri_to_uri(path, charset) + domain = _make_cookie_domain(domain) + if isinstance(max_age, timedelta): + max_age = (max_age.days * 60 * 60 * 24) + max_age.seconds + if expires is not None: + if not isinstance(expires, string_types): + expires = cookie_date(expires) + elif max_age is not None and sync_expires: + expires = to_bytes(cookie_date(time() + max_age)) + + samesite = samesite.title() if samesite else None + if samesite not in ('Strict', 'Lax', None): + raise ValueError("invalid SameSite value; must be 'Strict', 'Lax' or None") + + buf = [key + b'=' + _cookie_quote(value)] + + # XXX: In theory all of these parameters that are not marked with `None` + # should be quoted. Because stdlib did not quote it before I did not + # want to introduce quoting there now. + for k, v, q in ((b'Domain', domain, True), + (b'Expires', expires, False,), + (b'Max-Age', max_age, False), + (b'Secure', secure, None), + (b'HttpOnly', httponly, None), + (b'Path', path, False), + (b'SameSite', samesite, False)): + if q is None: + if v: + buf.append(k) + continue + + if v is None: + continue + + tmp = bytearray(k) + if not isinstance(v, (bytes, bytearray)): + v = to_bytes(text_type(v), charset) + if q: + v = _cookie_quote(v) + tmp += b'=' + v + buf.append(bytes(tmp)) + + # The return value will be an incorrectly encoded latin1 header on + # Python 3 for consistency with the headers object and a bytestring + # on Python 2 because that's how the API makes more sense. + rv = b'; '.join(buf) + if not PY2: + rv = rv.decode('latin1') + + # Warn if the final value of the cookie is less than the limit. If the + # cookie is too large, then it may be silently ignored, which can be quite + # hard to debug. + cookie_size = len(rv) + + if max_size and cookie_size > max_size: + value_size = len(value) + warnings.warn( + 'The "{key}" cookie is too large: the value was {value_size} bytes' + ' but the header required {extra_size} extra bytes. The final size' + ' was {cookie_size} bytes but the limit is {max_size} bytes.' + ' Browsers may silently ignore cookies larger than this.'.format( + key=key, + value_size=value_size, + extra_size=cookie_size - value_size, + cookie_size=cookie_size, + max_size=max_size + ), + stacklevel=2 + ) + + return rv + + +def is_byte_range_valid(start, stop, length): + """Checks if a given byte content range is valid for the given length. + + .. versionadded:: 0.7 + """ + if (start is None) != (stop is None): + return False + elif start is None: + return length is None or length >= 0 + elif length is None: + return 0 <= start < stop + elif start >= stop: + return False + return 0 <= start < length + + +# circular dependency fun +from werkzeug.datastructures import Accept, HeaderSet, ETags, Authorization, \ + WWWAuthenticate, TypeConversionDict, IfRange, Range, ContentRange, \ + RequestCacheControl + + +# DEPRECATED +# backwards compatible imports +from werkzeug.datastructures import ( # noqa + MIMEAccept, CharsetAccept, LanguageAccept, Headers +) +from werkzeug.urls import iri_to_uri diff --git a/pyextra/werkzeug/local.py b/pyextra/werkzeug/local.py new file mode 100644 index 00000000000000..e6d7478a0fd070 --- /dev/null +++ b/pyextra/werkzeug/local.py @@ -0,0 +1,420 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.local + ~~~~~~~~~~~~~~ + + This module implements context-local objects. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import copy +from functools import update_wrapper +from werkzeug.wsgi import ClosingIterator +from werkzeug._compat import PY2, implements_bool + +# since each thread has its own greenlet we can just use those as identifiers +# for the context. If greenlets are not available we fall back to the +# current thread ident depending on where it is. +try: + from greenlet import getcurrent as get_ident +except ImportError: + try: + from thread import get_ident + except ImportError: + from _thread import get_ident + + +def release_local(local): + """Releases the contents of the local for the current context. + This makes it possible to use locals without a manager. + + Example:: + + >>> loc = Local() + >>> loc.foo = 42 + >>> release_local(loc) + >>> hasattr(loc, 'foo') + False + + With this function one can release :class:`Local` objects as well + as :class:`LocalStack` objects. However it is not possible to + release data held by proxies that way, one always has to retain + a reference to the underlying local object in order to be able + to release it. + + .. versionadded:: 0.6.1 + """ + local.__release_local__() + + +class Local(object): + __slots__ = ('__storage__', '__ident_func__') + + def __init__(self): + object.__setattr__(self, '__storage__', {}) + object.__setattr__(self, '__ident_func__', get_ident) + + def __iter__(self): + return iter(self.__storage__.items()) + + def __call__(self, proxy): + """Create a proxy for a name.""" + return LocalProxy(self, proxy) + + def __release_local__(self): + self.__storage__.pop(self.__ident_func__(), None) + + def __getattr__(self, name): + try: + return self.__storage__[self.__ident_func__()][name] + except KeyError: + raise AttributeError(name) + + def __setattr__(self, name, value): + ident = self.__ident_func__() + storage = self.__storage__ + try: + storage[ident][name] = value + except KeyError: + storage[ident] = {name: value} + + def __delattr__(self, name): + try: + del self.__storage__[self.__ident_func__()][name] + except KeyError: + raise AttributeError(name) + + +class LocalStack(object): + + """This class works similar to a :class:`Local` but keeps a stack + of objects instead. This is best explained with an example:: + + >>> ls = LocalStack() + >>> ls.push(42) + >>> ls.top + 42 + >>> ls.push(23) + >>> ls.top + 23 + >>> ls.pop() + 23 + >>> ls.top + 42 + + They can be force released by using a :class:`LocalManager` or with + the :func:`release_local` function but the correct way is to pop the + item from the stack after using. When the stack is empty it will + no longer be bound to the current context (and as such released). + + By calling the stack without arguments it returns a proxy that resolves to + the topmost item on the stack. + + .. versionadded:: 0.6.1 + """ + + def __init__(self): + self._local = Local() + + def __release_local__(self): + self._local.__release_local__() + + def _get__ident_func__(self): + return self._local.__ident_func__ + + def _set__ident_func__(self, value): + object.__setattr__(self._local, '__ident_func__', value) + __ident_func__ = property(_get__ident_func__, _set__ident_func__) + del _get__ident_func__, _set__ident_func__ + + def __call__(self): + def _lookup(): + rv = self.top + if rv is None: + raise RuntimeError('object unbound') + return rv + return LocalProxy(_lookup) + + def push(self, obj): + """Pushes a new item to the stack""" + rv = getattr(self._local, 'stack', None) + if rv is None: + self._local.stack = rv = [] + rv.append(obj) + return rv + + def pop(self): + """Removes the topmost item from the stack, will return the + old value or `None` if the stack was already empty. + """ + stack = getattr(self._local, 'stack', None) + if stack is None: + return None + elif len(stack) == 1: + release_local(self._local) + return stack[-1] + else: + return stack.pop() + + @property + def top(self): + """The topmost item on the stack. If the stack is empty, + `None` is returned. + """ + try: + return self._local.stack[-1] + except (AttributeError, IndexError): + return None + + +class LocalManager(object): + + """Local objects cannot manage themselves. For that you need a local + manager. You can pass a local manager multiple locals or add them later + by appending them to `manager.locals`. Every time the manager cleans up, + it will clean up all the data left in the locals for this context. + + The `ident_func` parameter can be added to override the default ident + function for the wrapped locals. + + .. versionchanged:: 0.6.1 + Instead of a manager the :func:`release_local` function can be used + as well. + + .. versionchanged:: 0.7 + `ident_func` was added. + """ + + def __init__(self, locals=None, ident_func=None): + if locals is None: + self.locals = [] + elif isinstance(locals, Local): + self.locals = [locals] + else: + self.locals = list(locals) + if ident_func is not None: + self.ident_func = ident_func + for local in self.locals: + object.__setattr__(local, '__ident_func__', ident_func) + else: + self.ident_func = get_ident + + def get_ident(self): + """Return the context identifier the local objects use internally for + this context. You cannot override this method to change the behavior + but use it to link other context local objects (such as SQLAlchemy's + scoped sessions) to the Werkzeug locals. + + .. versionchanged:: 0.7 + You can pass a different ident function to the local manager that + will then be propagated to all the locals passed to the + constructor. + """ + return self.ident_func() + + def cleanup(self): + """Manually clean up the data in the locals for this context. Call + this at the end of the request or use `make_middleware()`. + """ + for local in self.locals: + release_local(local) + + def make_middleware(self, app): + """Wrap a WSGI application so that cleaning up happens after + request end. + """ + def application(environ, start_response): + return ClosingIterator(app(environ, start_response), self.cleanup) + return application + + def middleware(self, func): + """Like `make_middleware` but for decorating functions. + + Example usage:: + + @manager.middleware + def application(environ, start_response): + ... + + The difference to `make_middleware` is that the function passed + will have all the arguments copied from the inner application + (name, docstring, module). + """ + return update_wrapper(self.make_middleware(func), func) + + def __repr__(self): + return '<%s storages: %d>' % ( + self.__class__.__name__, + len(self.locals) + ) + + +@implements_bool +class LocalProxy(object): + + """Acts as a proxy for a werkzeug local. Forwards all operations to + a proxied object. The only operations not supported for forwarding + are right handed operands and any kind of assignment. + + Example usage:: + + from werkzeug.local import Local + l = Local() + + # these are proxies + request = l('request') + user = l('user') + + + from werkzeug.local import LocalStack + _response_local = LocalStack() + + # this is a proxy + response = _response_local() + + Whenever something is bound to l.user / l.request the proxy objects + will forward all operations. If no object is bound a :exc:`RuntimeError` + will be raised. + + To create proxies to :class:`Local` or :class:`LocalStack` objects, + call the object as shown above. If you want to have a proxy to an + object looked up by a function, you can (as of Werkzeug 0.6.1) pass + a function to the :class:`LocalProxy` constructor:: + + session = LocalProxy(lambda: get_current_request().session) + + .. versionchanged:: 0.6.1 + The class can be instantiated with a callable as well now. + """ + __slots__ = ('__local', '__dict__', '__name__', '__wrapped__') + + def __init__(self, local, name=None): + object.__setattr__(self, '_LocalProxy__local', local) + object.__setattr__(self, '__name__', name) + if callable(local) and not hasattr(local, '__release_local__'): + # "local" is a callable that is not an instance of Local or + # LocalManager: mark it as a wrapped function. + object.__setattr__(self, '__wrapped__', local) + + def _get_current_object(self): + """Return the current object. This is useful if you want the real + object behind the proxy at a time for performance reasons or because + you want to pass the object into a different context. + """ + if not hasattr(self.__local, '__release_local__'): + return self.__local() + try: + return getattr(self.__local, self.__name__) + except AttributeError: + raise RuntimeError('no object bound to %s' % self.__name__) + + @property + def __dict__(self): + try: + return self._get_current_object().__dict__ + except RuntimeError: + raise AttributeError('__dict__') + + def __repr__(self): + try: + obj = self._get_current_object() + except RuntimeError: + return '<%s unbound>' % self.__class__.__name__ + return repr(obj) + + def __bool__(self): + try: + return bool(self._get_current_object()) + except RuntimeError: + return False + + def __unicode__(self): + try: + return unicode(self._get_current_object()) # noqa + except RuntimeError: + return repr(self) + + def __dir__(self): + try: + return dir(self._get_current_object()) + except RuntimeError: + return [] + + def __getattr__(self, name): + if name == '__members__': + return dir(self._get_current_object()) + return getattr(self._get_current_object(), name) + + def __setitem__(self, key, value): + self._get_current_object()[key] = value + + def __delitem__(self, key): + del self._get_current_object()[key] + + if PY2: + __getslice__ = lambda x, i, j: x._get_current_object()[i:j] + + def __setslice__(self, i, j, seq): + self._get_current_object()[i:j] = seq + + def __delslice__(self, i, j): + del self._get_current_object()[i:j] + + __setattr__ = lambda x, n, v: setattr(x._get_current_object(), n, v) + __delattr__ = lambda x, n: delattr(x._get_current_object(), n) + __str__ = lambda x: str(x._get_current_object()) + __lt__ = lambda x, o: x._get_current_object() < o + __le__ = lambda x, o: x._get_current_object() <= o + __eq__ = lambda x, o: x._get_current_object() == o + __ne__ = lambda x, o: x._get_current_object() != o + __gt__ = lambda x, o: x._get_current_object() > o + __ge__ = lambda x, o: x._get_current_object() >= o + __cmp__ = lambda x, o: cmp(x._get_current_object(), o) # noqa + __hash__ = lambda x: hash(x._get_current_object()) + __call__ = lambda x, *a, **kw: x._get_current_object()(*a, **kw) + __len__ = lambda x: len(x._get_current_object()) + __getitem__ = lambda x, i: x._get_current_object()[i] + __iter__ = lambda x: iter(x._get_current_object()) + __contains__ = lambda x, i: i in x._get_current_object() + __add__ = lambda x, o: x._get_current_object() + o + __sub__ = lambda x, o: x._get_current_object() - o + __mul__ = lambda x, o: x._get_current_object() * o + __floordiv__ = lambda x, o: x._get_current_object() // o + __mod__ = lambda x, o: x._get_current_object() % o + __divmod__ = lambda x, o: x._get_current_object().__divmod__(o) + __pow__ = lambda x, o: x._get_current_object() ** o + __lshift__ = lambda x, o: x._get_current_object() << o + __rshift__ = lambda x, o: x._get_current_object() >> o + __and__ = lambda x, o: x._get_current_object() & o + __xor__ = lambda x, o: x._get_current_object() ^ o + __or__ = lambda x, o: x._get_current_object() | o + __div__ = lambda x, o: x._get_current_object().__div__(o) + __truediv__ = lambda x, o: x._get_current_object().__truediv__(o) + __neg__ = lambda x: -(x._get_current_object()) + __pos__ = lambda x: +(x._get_current_object()) + __abs__ = lambda x: abs(x._get_current_object()) + __invert__ = lambda x: ~(x._get_current_object()) + __complex__ = lambda x: complex(x._get_current_object()) + __int__ = lambda x: int(x._get_current_object()) + __long__ = lambda x: long(x._get_current_object()) # noqa + __float__ = lambda x: float(x._get_current_object()) + __oct__ = lambda x: oct(x._get_current_object()) + __hex__ = lambda x: hex(x._get_current_object()) + __index__ = lambda x: x._get_current_object().__index__() + __coerce__ = lambda x, o: x._get_current_object().__coerce__(x, o) + __enter__ = lambda x: x._get_current_object().__enter__() + __exit__ = lambda x, *a, **kw: x._get_current_object().__exit__(*a, **kw) + __radd__ = lambda x, o: o + x._get_current_object() + __rsub__ = lambda x, o: o - x._get_current_object() + __rmul__ = lambda x, o: o * x._get_current_object() + __rdiv__ = lambda x, o: o / x._get_current_object() + if PY2: + __rtruediv__ = lambda x, o: x._get_current_object().__rtruediv__(o) + else: + __rtruediv__ = __rdiv__ + __rfloordiv__ = lambda x, o: o // x._get_current_object() + __rmod__ = lambda x, o: o % x._get_current_object() + __rdivmod__ = lambda x, o: x._get_current_object().__rdivmod__(o) + __copy__ = lambda x: copy.copy(x._get_current_object()) + __deepcopy__ = lambda x, memo: copy.deepcopy(x._get_current_object(), memo) diff --git a/pyextra/werkzeug/posixemulation.py b/pyextra/werkzeug/posixemulation.py new file mode 100644 index 00000000000000..8fd6314f28a2b7 --- /dev/null +++ b/pyextra/werkzeug/posixemulation.py @@ -0,0 +1,106 @@ +# -*- coding: utf-8 -*- +r""" + werkzeug.posixemulation + ~~~~~~~~~~~~~~~~~~~~~~~ + + Provides a POSIX emulation for some features that are relevant to + web applications. The main purpose is to simplify support for + systems such as Windows NT that are not 100% POSIX compatible. + + Currently this only implements a :func:`rename` function that + follows POSIX semantics. Eg: if the target file already exists it + will be replaced without asking. + + This module was introduced in 0.6.1 and is not a public interface. + It might become one in later versions of Werkzeug. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import sys +import os +import errno +import time +import random + +from ._compat import to_unicode +from .filesystem import get_filesystem_encoding + + +can_rename_open_file = False +if os.name == 'nt': # pragma: no cover + _rename = lambda src, dst: False + _rename_atomic = lambda src, dst: False + + try: + import ctypes + + _MOVEFILE_REPLACE_EXISTING = 0x1 + _MOVEFILE_WRITE_THROUGH = 0x8 + _MoveFileEx = ctypes.windll.kernel32.MoveFileExW + + def _rename(src, dst): + src = to_unicode(src, get_filesystem_encoding()) + dst = to_unicode(dst, get_filesystem_encoding()) + if _rename_atomic(src, dst): + return True + retry = 0 + rv = False + while not rv and retry < 100: + rv = _MoveFileEx(src, dst, _MOVEFILE_REPLACE_EXISTING | + _MOVEFILE_WRITE_THROUGH) + if not rv: + time.sleep(0.001) + retry += 1 + return rv + + # new in Vista and Windows Server 2008 + _CreateTransaction = ctypes.windll.ktmw32.CreateTransaction + _CommitTransaction = ctypes.windll.ktmw32.CommitTransaction + _MoveFileTransacted = ctypes.windll.kernel32.MoveFileTransactedW + _CloseHandle = ctypes.windll.kernel32.CloseHandle + can_rename_open_file = True + + def _rename_atomic(src, dst): + ta = _CreateTransaction(None, 0, 0, 0, 0, 1000, 'Werkzeug rename') + if ta == -1: + return False + try: + retry = 0 + rv = False + while not rv and retry < 100: + rv = _MoveFileTransacted(src, dst, None, None, + _MOVEFILE_REPLACE_EXISTING | + _MOVEFILE_WRITE_THROUGH, ta) + if rv: + rv = _CommitTransaction(ta) + break + else: + time.sleep(0.001) + retry += 1 + return rv + finally: + _CloseHandle(ta) + except Exception: + pass + + def rename(src, dst): + # Try atomic or pseudo-atomic rename + if _rename(src, dst): + return + # Fall back to "move away and replace" + try: + os.rename(src, dst) + except OSError as e: + if e.errno != errno.EEXIST: + raise + old = "%s-%08x" % (dst, random.randint(0, sys.maxint)) + os.rename(dst, old) + os.rename(src, dst) + try: + os.unlink(old) + except Exception: + pass +else: + rename = os.rename + can_rename_open_file = True diff --git a/pyextra/werkzeug/routing.py b/pyextra/werkzeug/routing.py new file mode 100644 index 00000000000000..2e4e2f42c1c264 --- /dev/null +++ b/pyextra/werkzeug/routing.py @@ -0,0 +1,1792 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.routing + ~~~~~~~~~~~~~~~~ + + When it comes to combining multiple controller or view functions (however + you want to call them) you need a dispatcher. A simple way would be + applying regular expression tests on the ``PATH_INFO`` and calling + registered callback functions that return the value then. + + This module implements a much more powerful system than simple regular + expression matching because it can also convert values in the URLs and + build URLs. + + Here a simple example that creates an URL map for an application with + two subdomains (www and kb) and some URL rules: + + >>> m = Map([ + ... # Static URLs + ... Rule('/', endpoint='static/index'), + ... Rule('/about', endpoint='static/about'), + ... Rule('/help', endpoint='static/help'), + ... # Knowledge Base + ... Subdomain('kb', [ + ... Rule('/', endpoint='kb/index'), + ... Rule('/browse/', endpoint='kb/browse'), + ... Rule('/browse//', endpoint='kb/browse'), + ... Rule('/browse//', endpoint='kb/browse') + ... ]) + ... ], default_subdomain='www') + + If the application doesn't use subdomains it's perfectly fine to not set + the default subdomain and not use the `Subdomain` rule factory. The endpoint + in the rules can be anything, for example import paths or unique + identifiers. The WSGI application can use those endpoints to get the + handler for that URL. It doesn't have to be a string at all but it's + recommended. + + Now it's possible to create a URL adapter for one of the subdomains and + build URLs: + + >>> c = m.bind('example.com') + >>> c.build("kb/browse", dict(id=42)) + 'http://kb.example.com/browse/42/' + >>> c.build("kb/browse", dict()) + 'http://kb.example.com/browse/' + >>> c.build("kb/browse", dict(id=42, page=3)) + 'http://kb.example.com/browse/42/3' + >>> c.build("static/about") + '/about' + >>> c.build("static/index", force_external=True) + 'http://www.example.com/' + + >>> c = m.bind('example.com', subdomain='kb') + >>> c.build("static/about") + 'http://www.example.com/about' + + The first argument to bind is the server name *without* the subdomain. + Per default it will assume that the script is mounted on the root, but + often that's not the case so you can provide the real mount point as + second argument: + + >>> c = m.bind('example.com', '/applications/example') + + The third argument can be the subdomain, if not given the default + subdomain is used. For more details about binding have a look at the + documentation of the `MapAdapter`. + + And here is how you can match URLs: + + >>> c = m.bind('example.com') + >>> c.match("/") + ('static/index', {}) + >>> c.match("/about") + ('static/about', {}) + >>> c = m.bind('example.com', '/', 'kb') + >>> c.match("/") + ('kb/index', {}) + >>> c.match("/browse/42/23") + ('kb/browse', {'id': 42, 'page': 23}) + + If matching fails you get a `NotFound` exception, if the rule thinks + it's a good idea to redirect (for example because the URL was defined + to have a slash at the end but the request was missing that slash) it + will raise a `RequestRedirect` exception. Both are subclasses of the + `HTTPException` so you can use those errors as responses in the + application. + + If matching succeeded but the URL rule was incompatible to the given + method (for example there were only rules for `GET` and `HEAD` and + routing system tried to match a `POST` request) a `MethodNotAllowed` + exception is raised. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import difflib +import re +import uuid +import posixpath + +from pprint import pformat +from threading import Lock + +from werkzeug.urls import url_encode, url_quote, url_join +from werkzeug.utils import redirect, format_string +from werkzeug.exceptions import HTTPException, NotFound, MethodNotAllowed, \ + BadHost +from werkzeug._internal import _get_environ, _encode_idna +from werkzeug._compat import itervalues, iteritems, to_unicode, to_bytes, \ + text_type, string_types, native_string_result, \ + implements_to_string, wsgi_decoding_dance +from werkzeug.datastructures import ImmutableDict, MultiDict +from werkzeug.utils import cached_property + + +_rule_re = re.compile(r''' + (?P[^<]*) # static rule data + < + (?: + (?P[a-zA-Z_][a-zA-Z0-9_]*) # converter name + (?:\((?P.*?)\))? # converter arguments + \: # variable delimiter + )? + (?P[a-zA-Z_][a-zA-Z0-9_]*) # variable name + > +''', re.VERBOSE) +_simple_rule_re = re.compile(r'<([^>]+)>') +_converter_args_re = re.compile(r''' + ((?P\w+)\s*=\s*)? + (?P + True|False| + \d+.\d+| + \d+.| + \d+| + [\w\d_.]+| + [urUR]?(?P"[^"]*?"|'[^']*') + )\s*, +''', re.VERBOSE | re.UNICODE) + + +_PYTHON_CONSTANTS = { + 'None': None, + 'True': True, + 'False': False +} + + +def _pythonize(value): + if value in _PYTHON_CONSTANTS: + return _PYTHON_CONSTANTS[value] + for convert in int, float: + try: + return convert(value) + except ValueError: + pass + if value[:1] == value[-1:] and value[0] in '"\'': + value = value[1:-1] + return text_type(value) + + +def parse_converter_args(argstr): + argstr += ',' + args = [] + kwargs = {} + + for item in _converter_args_re.finditer(argstr): + value = item.group('stringval') + if value is None: + value = item.group('value') + value = _pythonize(value) + if not item.group('name'): + args.append(value) + else: + name = item.group('name') + kwargs[name] = value + + return tuple(args), kwargs + + +def parse_rule(rule): + """Parse a rule and return it as generator. Each iteration yields tuples + in the form ``(converter, arguments, variable)``. If the converter is + `None` it's a static url part, otherwise it's a dynamic one. + + :internal: + """ + pos = 0 + end = len(rule) + do_match = _rule_re.match + used_names = set() + while pos < end: + m = do_match(rule, pos) + if m is None: + break + data = m.groupdict() + if data['static']: + yield None, None, data['static'] + variable = data['variable'] + converter = data['converter'] or 'default' + if variable in used_names: + raise ValueError('variable name %r used twice.' % variable) + used_names.add(variable) + yield converter, data['args'] or None, variable + pos = m.end() + if pos < end: + remaining = rule[pos:] + if '>' in remaining or '<' in remaining: + raise ValueError('malformed url rule: %r' % rule) + yield None, None, remaining + + +class RoutingException(Exception): + + """Special exceptions that require the application to redirect, notifying + about missing urls, etc. + + :internal: + """ + + +class RequestRedirect(HTTPException, RoutingException): + + """Raise if the map requests a redirect. This is for example the case if + `strict_slashes` are activated and an url that requires a trailing slash. + + The attribute `new_url` contains the absolute destination url. + """ + code = 301 + + def __init__(self, new_url): + RoutingException.__init__(self, new_url) + self.new_url = new_url + + def get_response(self, environ): + return redirect(self.new_url, self.code) + + +class RequestSlash(RoutingException): + + """Internal exception.""" + + +class RequestAliasRedirect(RoutingException): + + """This rule is an alias and wants to redirect to the canonical URL.""" + + def __init__(self, matched_values): + self.matched_values = matched_values + + +@implements_to_string +class BuildError(RoutingException, LookupError): + + """Raised if the build system cannot find a URL for an endpoint with the + values provided. + """ + + def __init__(self, endpoint, values, method, adapter=None): + LookupError.__init__(self, endpoint, values, method) + self.endpoint = endpoint + self.values = values + self.method = method + self.adapter = adapter + + @cached_property + def suggested(self): + return self.closest_rule(self.adapter) + + def closest_rule(self, adapter): + def _score_rule(rule): + return sum([ + 0.98 * difflib.SequenceMatcher( + None, rule.endpoint, self.endpoint + ).ratio(), + 0.01 * bool(set(self.values or ()).issubset(rule.arguments)), + 0.01 * bool(rule.methods and self.method in rule.methods) + ]) + + if adapter and adapter.map._rules: + return max(adapter.map._rules, key=_score_rule) + + def __str__(self): + message = [] + message.append('Could not build url for endpoint %r' % self.endpoint) + if self.method: + message.append(' (%r)' % self.method) + if self.values: + message.append(' with values %r' % sorted(self.values.keys())) + message.append('.') + if self.suggested: + if self.endpoint == self.suggested.endpoint: + if self.method and self.method not in self.suggested.methods: + message.append(' Did you mean to use methods %r?' % sorted( + self.suggested.methods + )) + missing_values = self.suggested.arguments.union( + set(self.suggested.defaults or ()) + ) - set(self.values.keys()) + if missing_values: + message.append( + ' Did you forget to specify values %r?' % + sorted(missing_values) + ) + else: + message.append( + ' Did you mean %r instead?' % self.suggested.endpoint + ) + return u''.join(message) + + +class ValidationError(ValueError): + + """Validation error. If a rule converter raises this exception the rule + does not match the current URL and the next URL is tried. + """ + + +class RuleFactory(object): + + """As soon as you have more complex URL setups it's a good idea to use rule + factories to avoid repetitive tasks. Some of them are builtin, others can + be added by subclassing `RuleFactory` and overriding `get_rules`. + """ + + def get_rules(self, map): + """Subclasses of `RuleFactory` have to override this method and return + an iterable of rules.""" + raise NotImplementedError() + + +class Subdomain(RuleFactory): + + """All URLs provided by this factory have the subdomain set to a + specific domain. For example if you want to use the subdomain for + the current language this can be a good setup:: + + url_map = Map([ + Rule('/', endpoint='#select_language'), + Subdomain('', [ + Rule('/', endpoint='index'), + Rule('/about', endpoint='about'), + Rule('/help', endpoint='help') + ]) + ]) + + All the rules except for the ``'#select_language'`` endpoint will now + listen on a two letter long subdomain that holds the language code + for the current request. + """ + + def __init__(self, subdomain, rules): + self.subdomain = subdomain + self.rules = rules + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + rule = rule.empty() + rule.subdomain = self.subdomain + yield rule + + +class Submount(RuleFactory): + + """Like `Subdomain` but prefixes the URL rule with a given string:: + + url_map = Map([ + Rule('/', endpoint='index'), + Submount('/blog', [ + Rule('/', endpoint='blog/index'), + Rule('/entry/', endpoint='blog/show') + ]) + ]) + + Now the rule ``'blog/show'`` matches ``/blog/entry/``. + """ + + def __init__(self, path, rules): + self.path = path.rstrip('/') + self.rules = rules + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + rule = rule.empty() + rule.rule = self.path + rule.rule + yield rule + + +class EndpointPrefix(RuleFactory): + + """Prefixes all endpoints (which must be strings for this factory) with + another string. This can be useful for sub applications:: + + url_map = Map([ + Rule('/', endpoint='index'), + EndpointPrefix('blog/', [Submount('/blog', [ + Rule('/', endpoint='index'), + Rule('/entry/', endpoint='show') + ])]) + ]) + """ + + def __init__(self, prefix, rules): + self.prefix = prefix + self.rules = rules + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + rule = rule.empty() + rule.endpoint = self.prefix + rule.endpoint + yield rule + + +class RuleTemplate(object): + + """Returns copies of the rules wrapped and expands string templates in + the endpoint, rule, defaults or subdomain sections. + + Here a small example for such a rule template:: + + from werkzeug.routing import Map, Rule, RuleTemplate + + resource = RuleTemplate([ + Rule('/$name/', endpoint='$name.list'), + Rule('/$name/', endpoint='$name.show') + ]) + + url_map = Map([resource(name='user'), resource(name='page')]) + + When a rule template is called the keyword arguments are used to + replace the placeholders in all the string parameters. + """ + + def __init__(self, rules): + self.rules = list(rules) + + def __call__(self, *args, **kwargs): + return RuleTemplateFactory(self.rules, dict(*args, **kwargs)) + + +class RuleTemplateFactory(RuleFactory): + + """A factory that fills in template variables into rules. Used by + `RuleTemplate` internally. + + :internal: + """ + + def __init__(self, rules, context): + self.rules = rules + self.context = context + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + new_defaults = subdomain = None + if rule.defaults: + new_defaults = {} + for key, value in iteritems(rule.defaults): + if isinstance(value, string_types): + value = format_string(value, self.context) + new_defaults[key] = value + if rule.subdomain is not None: + subdomain = format_string(rule.subdomain, self.context) + new_endpoint = rule.endpoint + if isinstance(new_endpoint, string_types): + new_endpoint = format_string(new_endpoint, self.context) + yield Rule( + format_string(rule.rule, self.context), + new_defaults, + subdomain, + rule.methods, + rule.build_only, + new_endpoint, + rule.strict_slashes + ) + + +@implements_to_string +class Rule(RuleFactory): + + """A Rule represents one URL pattern. There are some options for `Rule` + that change the way it behaves and are passed to the `Rule` constructor. + Note that besides the rule-string all arguments *must* be keyword arguments + in order to not break the application on Werkzeug upgrades. + + `string` + Rule strings basically are just normal URL paths with placeholders in + the format ```` where the converter and the + arguments are optional. If no converter is defined the `default` + converter is used which means `string` in the normal configuration. + + URL rules that end with a slash are branch URLs, others are leaves. + If you have `strict_slashes` enabled (which is the default), all + branch URLs that are matched without a trailing slash will trigger a + redirect to the same URL with the missing slash appended. + + The converters are defined on the `Map`. + + `endpoint` + The endpoint for this rule. This can be anything. A reference to a + function, a string, a number etc. The preferred way is using a string + because the endpoint is used for URL generation. + + `defaults` + An optional dict with defaults for other rules with the same endpoint. + This is a bit tricky but useful if you want to have unique URLs:: + + url_map = Map([ + Rule('/all/', defaults={'page': 1}, endpoint='all_entries'), + Rule('/all/page/', endpoint='all_entries') + ]) + + If a user now visits ``http://example.com/all/page/1`` he will be + redirected to ``http://example.com/all/``. If `redirect_defaults` is + disabled on the `Map` instance this will only affect the URL + generation. + + `subdomain` + The subdomain rule string for this rule. If not specified the rule + only matches for the `default_subdomain` of the map. If the map is + not bound to a subdomain this feature is disabled. + + Can be useful if you want to have user profiles on different subdomains + and all subdomains are forwarded to your application:: + + url_map = Map([ + Rule('/', subdomain='', endpoint='user/homepage'), + Rule('/stats', subdomain='', endpoint='user/stats') + ]) + + `methods` + A sequence of http methods this rule applies to. If not specified, all + methods are allowed. For example this can be useful if you want different + endpoints for `POST` and `GET`. If methods are defined and the path + matches but the method matched against is not in this list or in the + list of another rule for that path the error raised is of the type + `MethodNotAllowed` rather than `NotFound`. If `GET` is present in the + list of methods and `HEAD` is not, `HEAD` is added automatically. + + .. versionchanged:: 0.6.1 + `HEAD` is now automatically added to the methods if `GET` is + present. The reason for this is that existing code often did not + work properly in servers not rewriting `HEAD` to `GET` + automatically and it was not documented how `HEAD` should be + treated. This was considered a bug in Werkzeug because of that. + + `strict_slashes` + Override the `Map` setting for `strict_slashes` only for this rule. If + not specified the `Map` setting is used. + + `build_only` + Set this to True and the rule will never match but will create a URL + that can be build. This is useful if you have resources on a subdomain + or folder that are not handled by the WSGI application (like static data) + + `redirect_to` + If given this must be either a string or callable. In case of a + callable it's called with the url adapter that triggered the match and + the values of the URL as keyword arguments and has to return the target + for the redirect, otherwise it has to be a string with placeholders in + rule syntax:: + + def foo_with_slug(adapter, id): + # ask the database for the slug for the old id. this of + # course has nothing to do with werkzeug. + return 'foo/' + Foo.get_slug_for_id(id) + + url_map = Map([ + Rule('/foo/', endpoint='foo'), + Rule('/some/old/url/', redirect_to='foo/'), + Rule('/other/old/url/', redirect_to=foo_with_slug) + ]) + + When the rule is matched the routing system will raise a + `RequestRedirect` exception with the target for the redirect. + + Keep in mind that the URL will be joined against the URL root of the + script so don't use a leading slash on the target URL unless you + really mean root of that domain. + + `alias` + If enabled this rule serves as an alias for another rule with the same + endpoint and arguments. + + `host` + If provided and the URL map has host matching enabled this can be + used to provide a match rule for the whole host. This also means + that the subdomain feature is disabled. + + .. versionadded:: 0.7 + The `alias` and `host` parameters were added. + """ + + def __init__(self, string, defaults=None, subdomain=None, methods=None, + build_only=False, endpoint=None, strict_slashes=None, + redirect_to=None, alias=False, host=None): + if not string.startswith('/'): + raise ValueError('urls must start with a leading slash') + self.rule = string + self.is_leaf = not string.endswith('/') + + self.map = None + self.strict_slashes = strict_slashes + self.subdomain = subdomain + self.host = host + self.defaults = defaults + self.build_only = build_only + self.alias = alias + if methods is None: + self.methods = None + else: + if isinstance(methods, str): + raise TypeError('param `methods` should be `Iterable[str]`, not `str`') + self.methods = set([x.upper() for x in methods]) + if 'HEAD' not in self.methods and 'GET' in self.methods: + self.methods.add('HEAD') + self.endpoint = endpoint + self.redirect_to = redirect_to + + if defaults: + self.arguments = set(map(str, defaults)) + else: + self.arguments = set() + self._trace = self._converters = self._regex = self._argument_weights = None + + def empty(self): + """ + Return an unbound copy of this rule. + + This can be useful if want to reuse an already bound URL for another + map. See ``get_empty_kwargs`` to override what keyword arguments are + provided to the new copy. + """ + return type(self)(self.rule, **self.get_empty_kwargs()) + + def get_empty_kwargs(self): + """ + Provides kwargs for instantiating empty copy with empty() + + Use this method to provide custom keyword arguments to the subclass of + ``Rule`` when calling ``some_rule.empty()``. Helpful when the subclass + has custom keyword arguments that are needed at instantiation. + + Must return a ``dict`` that will be provided as kwargs to the new + instance of ``Rule``, following the initial ``self.rule`` value which + is always provided as the first, required positional argument. + """ + defaults = None + if self.defaults: + defaults = dict(self.defaults) + return dict(defaults=defaults, subdomain=self.subdomain, + methods=self.methods, build_only=self.build_only, + endpoint=self.endpoint, strict_slashes=self.strict_slashes, + redirect_to=self.redirect_to, alias=self.alias, + host=self.host) + + def get_rules(self, map): + yield self + + def refresh(self): + """Rebinds and refreshes the URL. Call this if you modified the + rule in place. + + :internal: + """ + self.bind(self.map, rebind=True) + + def bind(self, map, rebind=False): + """Bind the url to a map and create a regular expression based on + the information from the rule itself and the defaults from the map. + + :internal: + """ + if self.map is not None and not rebind: + raise RuntimeError('url rule %r already bound to map %r' % + (self, self.map)) + self.map = map + if self.strict_slashes is None: + self.strict_slashes = map.strict_slashes + if self.subdomain is None: + self.subdomain = map.default_subdomain + self.compile() + + def get_converter(self, variable_name, converter_name, args, kwargs): + """Looks up the converter for the given parameter. + + .. versionadded:: 0.9 + """ + if converter_name not in self.map.converters: + raise LookupError('the converter %r does not exist' % converter_name) + return self.map.converters[converter_name](self.map, *args, **kwargs) + + def compile(self): + """Compiles the regular expression and stores it.""" + assert self.map is not None, 'rule not bound' + + if self.map.host_matching: + domain_rule = self.host or '' + else: + domain_rule = self.subdomain or '' + + self._trace = [] + self._converters = {} + self._static_weights = [] + self._argument_weights = [] + regex_parts = [] + + def _build_regex(rule): + index = 0 + for converter, arguments, variable in parse_rule(rule): + if converter is None: + regex_parts.append(re.escape(variable)) + self._trace.append((False, variable)) + for part in variable.split('/'): + if part: + self._static_weights.append((index, -len(part))) + else: + if arguments: + c_args, c_kwargs = parse_converter_args(arguments) + else: + c_args = () + c_kwargs = {} + convobj = self.get_converter( + variable, converter, c_args, c_kwargs) + regex_parts.append('(?P<%s>%s)' % (variable, convobj.regex)) + self._converters[variable] = convobj + self._trace.append((True, variable)) + self._argument_weights.append(convobj.weight) + self.arguments.add(str(variable)) + index = index + 1 + + _build_regex(domain_rule) + regex_parts.append('\\|') + self._trace.append((False, '|')) + _build_regex(self.is_leaf and self.rule or self.rule.rstrip('/')) + if not self.is_leaf: + self._trace.append((False, '/')) + + if self.build_only: + return + regex = r'^%s%s$' % ( + u''.join(regex_parts), + (not self.is_leaf or not self.strict_slashes) and + '(?/?)' or '' + ) + self._regex = re.compile(regex, re.UNICODE) + + def match(self, path, method=None): + """Check if the rule matches a given path. Path is a string in the + form ``"subdomain|/path"`` and is assembled by the map. If + the map is doing host matching the subdomain part will be the host + instead. + + If the rule matches a dict with the converted values is returned, + otherwise the return value is `None`. + + :internal: + """ + if not self.build_only: + m = self._regex.search(path) + if m is not None: + groups = m.groupdict() + # we have a folder like part of the url without a trailing + # slash and strict slashes enabled. raise an exception that + # tells the map to redirect to the same url but with a + # trailing slash + if self.strict_slashes and not self.is_leaf and \ + not groups.pop('__suffix__') and \ + (method is None or self.methods is None or + method in self.methods): + raise RequestSlash() + # if we are not in strict slashes mode we have to remove + # a __suffix__ + elif not self.strict_slashes: + del groups['__suffix__'] + + result = {} + for name, value in iteritems(groups): + try: + value = self._converters[name].to_python(value) + except ValidationError: + return + result[str(name)] = value + if self.defaults: + result.update(self.defaults) + + if self.alias and self.map.redirect_defaults: + raise RequestAliasRedirect(result) + + return result + + def build(self, values, append_unknown=True): + """Assembles the relative url for that rule and the subdomain. + If building doesn't work for some reasons `None` is returned. + + :internal: + """ + tmp = [] + add = tmp.append + processed = set(self.arguments) + for is_dynamic, data in self._trace: + if is_dynamic: + try: + add(self._converters[data].to_url(values[data])) + except ValidationError: + return + processed.add(data) + else: + add(url_quote(to_bytes(data, self.map.charset), safe='/:|+')) + domain_part, url = (u''.join(tmp)).split(u'|', 1) + + if append_unknown: + query_vars = MultiDict(values) + for key in processed: + if key in query_vars: + del query_vars[key] + + if query_vars: + url += u'?' + url_encode(query_vars, charset=self.map.charset, + sort=self.map.sort_parameters, + key=self.map.sort_key) + + return domain_part, url + + def provides_defaults_for(self, rule): + """Check if this rule has defaults for a given rule. + + :internal: + """ + return not self.build_only and self.defaults and \ + self.endpoint == rule.endpoint and self != rule and \ + self.arguments == rule.arguments + + def suitable_for(self, values, method=None): + """Check if the dict of values has enough data for url generation. + + :internal: + """ + # if a method was given explicitly and that method is not supported + # by this rule, this rule is not suitable. + if method is not None and self.methods is not None \ + and method not in self.methods: + return False + + defaults = self.defaults or () + + # all arguments required must be either in the defaults dict or + # the value dictionary otherwise it's not suitable + for key in self.arguments: + if key not in defaults and key not in values: + return False + + # in case defaults are given we ensure taht either the value was + # skipped or the value is the same as the default value. + if defaults: + for key, value in iteritems(defaults): + if key in values and value != values[key]: + return False + + return True + + def match_compare_key(self): + """The match compare key for sorting. + + Current implementation: + + 1. rules without any arguments come first for performance + reasons only as we expect them to match faster and some + common ones usually don't have any arguments (index pages etc.) + 2. rules with more static parts come first so the second argument + is the negative length of the number of the static weights. + 3. we order by static weights, which is a combination of index + and length + 4. The more complex rules come first so the next argument is the + negative length of the number of argument weights. + 5. lastly we order by the actual argument weights. + + :internal: + """ + return bool(self.arguments), -len(self._static_weights), self._static_weights,\ + -len(self._argument_weights), self._argument_weights + + def build_compare_key(self): + """The build compare key for sorting. + + :internal: + """ + return self.alias and 1 or 0, -len(self.arguments), \ + -len(self.defaults or ()) + + def __eq__(self, other): + return self.__class__ is other.__class__ and \ + self._trace == other._trace + + __hash__ = None + + def __ne__(self, other): + return not self.__eq__(other) + + def __str__(self): + return self.rule + + @native_string_result + def __repr__(self): + if self.map is None: + return u'<%s (unbound)>' % self.__class__.__name__ + tmp = [] + for is_dynamic, data in self._trace: + if is_dynamic: + tmp.append(u'<%s>' % data) + else: + tmp.append(data) + return u'<%s %s%s -> %s>' % ( + self.__class__.__name__, + repr((u''.join(tmp)).lstrip(u'|')).lstrip(u'u'), + self.methods is not None + and u' (%s)' % u', '.join(self.methods) + or u'', + self.endpoint + ) + + +class BaseConverter(object): + + """Base class for all converters.""" + regex = '[^/]+' + weight = 100 + + def __init__(self, map): + self.map = map + + def to_python(self, value): + return value + + def to_url(self, value): + return url_quote(value, charset=self.map.charset) + + +class UnicodeConverter(BaseConverter): + + """This converter is the default converter and accepts any string but + only one path segment. Thus the string can not include a slash. + + This is the default validator. + + Example:: + + Rule('/pages/'), + Rule('/') + + :param map: the :class:`Map`. + :param minlength: the minimum length of the string. Must be greater + or equal 1. + :param maxlength: the maximum length of the string. + :param length: the exact length of the string. + """ + + def __init__(self, map, minlength=1, maxlength=None, length=None): + BaseConverter.__init__(self, map) + if length is not None: + length = '{%d}' % int(length) + else: + if maxlength is None: + maxlength = '' + else: + maxlength = int(maxlength) + length = '{%s,%s}' % ( + int(minlength), + maxlength + ) + self.regex = '[^/]' + length + + +class AnyConverter(BaseConverter): + + """Matches one of the items provided. Items can either be Python + identifiers or strings:: + + Rule('/') + + :param map: the :class:`Map`. + :param items: this function accepts the possible items as positional + arguments. + """ + + def __init__(self, map, *items): + BaseConverter.__init__(self, map) + self.regex = '(?:%s)' % '|'.join([re.escape(x) for x in items]) + + +class PathConverter(BaseConverter): + + """Like the default :class:`UnicodeConverter`, but it also matches + slashes. This is useful for wikis and similar applications:: + + Rule('/') + Rule('//edit') + + :param map: the :class:`Map`. + """ + regex = '[^/].*?' + weight = 200 + + +class NumberConverter(BaseConverter): + + """Baseclass for `IntegerConverter` and `FloatConverter`. + + :internal: + """ + weight = 50 + + def __init__(self, map, fixed_digits=0, min=None, max=None): + BaseConverter.__init__(self, map) + self.fixed_digits = fixed_digits + self.min = min + self.max = max + + def to_python(self, value): + if (self.fixed_digits and len(value) != self.fixed_digits): + raise ValidationError() + value = self.num_convert(value) + if (self.min is not None and value < self.min) or \ + (self.max is not None and value > self.max): + raise ValidationError() + return value + + def to_url(self, value): + value = self.num_convert(value) + if self.fixed_digits: + value = ('%%0%sd' % self.fixed_digits) % value + return str(value) + + +class IntegerConverter(NumberConverter): + + """This converter only accepts integer values:: + + Rule('/page/') + + This converter does not support negative values. + + :param map: the :class:`Map`. + :param fixed_digits: the number of fixed digits in the URL. If you set + this to ``4`` for example, the application will + only match if the url looks like ``/0001/``. The + default is variable length. + :param min: the minimal value. + :param max: the maximal value. + """ + regex = r'\d+' + num_convert = int + + +class FloatConverter(NumberConverter): + + """This converter only accepts floating point values:: + + Rule('/probability/') + + This converter does not support negative values. + + :param map: the :class:`Map`. + :param min: the minimal value. + :param max: the maximal value. + """ + regex = r'\d+\.\d+' + num_convert = float + + def __init__(self, map, min=None, max=None): + NumberConverter.__init__(self, map, 0, min, max) + + +class UUIDConverter(BaseConverter): + + """This converter only accepts UUID strings:: + + Rule('/object/') + + .. versionadded:: 0.10 + + :param map: the :class:`Map`. + """ + regex = r'[A-Fa-f0-9]{8}-[A-Fa-f0-9]{4}-' \ + r'[A-Fa-f0-9]{4}-[A-Fa-f0-9]{4}-[A-Fa-f0-9]{12}' + + def to_python(self, value): + return uuid.UUID(value) + + def to_url(self, value): + return str(value) + + +#: the default converter mapping for the map. +DEFAULT_CONVERTERS = { + 'default': UnicodeConverter, + 'string': UnicodeConverter, + 'any': AnyConverter, + 'path': PathConverter, + 'int': IntegerConverter, + 'float': FloatConverter, + 'uuid': UUIDConverter, +} + + +class Map(object): + + """The map class stores all the URL rules and some configuration + parameters. Some of the configuration values are only stored on the + `Map` instance since those affect all rules, others are just defaults + and can be overridden for each rule. Note that you have to specify all + arguments besides the `rules` as keyword arguments! + + :param rules: sequence of url rules for this map. + :param default_subdomain: The default subdomain for rules without a + subdomain defined. + :param charset: charset of the url. defaults to ``"utf-8"`` + :param strict_slashes: Take care of trailing slashes. + :param redirect_defaults: This will redirect to the default rule if it + wasn't visited that way. This helps creating + unique URLs. + :param converters: A dict of converters that adds additional converters + to the list of converters. If you redefine one + converter this will override the original one. + :param sort_parameters: If set to `True` the url parameters are sorted. + See `url_encode` for more details. + :param sort_key: The sort key function for `url_encode`. + :param encoding_errors: the error method to use for decoding + :param host_matching: if set to `True` it enables the host matching + feature and disables the subdomain one. If + enabled the `host` parameter to rules is used + instead of the `subdomain` one. + + .. versionadded:: 0.5 + `sort_parameters` and `sort_key` was added. + + .. versionadded:: 0.7 + `encoding_errors` and `host_matching` was added. + """ + + #: .. versionadded:: 0.6 + #: a dict of default converters to be used. + default_converters = ImmutableDict(DEFAULT_CONVERTERS) + + def __init__(self, rules=None, default_subdomain='', charset='utf-8', + strict_slashes=True, redirect_defaults=True, + converters=None, sort_parameters=False, sort_key=None, + encoding_errors='replace', host_matching=False): + self._rules = [] + self._rules_by_endpoint = {} + self._remap = True + self._remap_lock = Lock() + + self.default_subdomain = default_subdomain + self.charset = charset + self.encoding_errors = encoding_errors + self.strict_slashes = strict_slashes + self.redirect_defaults = redirect_defaults + self.host_matching = host_matching + + self.converters = self.default_converters.copy() + if converters: + self.converters.update(converters) + + self.sort_parameters = sort_parameters + self.sort_key = sort_key + + for rulefactory in rules or (): + self.add(rulefactory) + + def is_endpoint_expecting(self, endpoint, *arguments): + """Iterate over all rules and check if the endpoint expects + the arguments provided. This is for example useful if you have + some URLs that expect a language code and others that do not and + you want to wrap the builder a bit so that the current language + code is automatically added if not provided but endpoints expect + it. + + :param endpoint: the endpoint to check. + :param arguments: this function accepts one or more arguments + as positional arguments. Each one of them is + checked. + """ + self.update() + arguments = set(arguments) + for rule in self._rules_by_endpoint[endpoint]: + if arguments.issubset(rule.arguments): + return True + return False + + def iter_rules(self, endpoint=None): + """Iterate over all rules or the rules of an endpoint. + + :param endpoint: if provided only the rules for that endpoint + are returned. + :return: an iterator + """ + self.update() + if endpoint is not None: + return iter(self._rules_by_endpoint[endpoint]) + return iter(self._rules) + + def add(self, rulefactory): + """Add a new rule or factory to the map and bind it. Requires that the + rule is not bound to another map. + + :param rulefactory: a :class:`Rule` or :class:`RuleFactory` + """ + for rule in rulefactory.get_rules(self): + rule.bind(self) + self._rules.append(rule) + self._rules_by_endpoint.setdefault(rule.endpoint, []).append(rule) + self._remap = True + + def bind(self, server_name, script_name=None, subdomain=None, + url_scheme='http', default_method='GET', path_info=None, + query_args=None): + """Return a new :class:`MapAdapter` with the details specified to the + call. Note that `script_name` will default to ``'/'`` if not further + specified or `None`. The `server_name` at least is a requirement + because the HTTP RFC requires absolute URLs for redirects and so all + redirect exceptions raised by Werkzeug will contain the full canonical + URL. + + If no path_info is passed to :meth:`match` it will use the default path + info passed to bind. While this doesn't really make sense for + manual bind calls, it's useful if you bind a map to a WSGI + environment which already contains the path info. + + `subdomain` will default to the `default_subdomain` for this map if + no defined. If there is no `default_subdomain` you cannot use the + subdomain feature. + + .. versionadded:: 0.7 + `query_args` added + + .. versionadded:: 0.8 + `query_args` can now also be a string. + """ + server_name = server_name.lower() + if self.host_matching: + if subdomain is not None: + raise RuntimeError('host matching enabled and a ' + 'subdomain was provided') + elif subdomain is None: + subdomain = self.default_subdomain + if script_name is None: + script_name = '/' + try: + server_name = _encode_idna(server_name) + except UnicodeError: + raise BadHost() + return MapAdapter(self, server_name, script_name, subdomain, + url_scheme, path_info, default_method, query_args) + + def bind_to_environ(self, environ, server_name=None, subdomain=None): + """Like :meth:`bind` but you can pass it an WSGI environment and it + will fetch the information from that dictionary. Note that because of + limitations in the protocol there is no way to get the current + subdomain and real `server_name` from the environment. If you don't + provide it, Werkzeug will use `SERVER_NAME` and `SERVER_PORT` (or + `HTTP_HOST` if provided) as used `server_name` with disabled subdomain + feature. + + If `subdomain` is `None` but an environment and a server name is + provided it will calculate the current subdomain automatically. + Example: `server_name` is ``'example.com'`` and the `SERVER_NAME` + in the wsgi `environ` is ``'staging.dev.example.com'`` the calculated + subdomain will be ``'staging.dev'``. + + If the object passed as environ has an environ attribute, the value of + this attribute is used instead. This allows you to pass request + objects. Additionally `PATH_INFO` added as a default of the + :class:`MapAdapter` so that you don't have to pass the path info to + the match method. + + .. versionchanged:: 0.5 + previously this method accepted a bogus `calculate_subdomain` + parameter that did not have any effect. It was removed because + of that. + + .. versionchanged:: 0.8 + This will no longer raise a ValueError when an unexpected server + name was passed. + + :param environ: a WSGI environment. + :param server_name: an optional server name hint (see above). + :param subdomain: optionally the current subdomain (see above). + """ + environ = _get_environ(environ) + + if 'HTTP_HOST' in environ: + wsgi_server_name = environ['HTTP_HOST'] + + if environ['wsgi.url_scheme'] == 'http' \ + and wsgi_server_name.endswith(':80'): + wsgi_server_name = wsgi_server_name[:-3] + elif environ['wsgi.url_scheme'] == 'https' \ + and wsgi_server_name.endswith(':443'): + wsgi_server_name = wsgi_server_name[:-4] + else: + wsgi_server_name = environ['SERVER_NAME'] + + if (environ['wsgi.url_scheme'], environ['SERVER_PORT']) not \ + in (('https', '443'), ('http', '80')): + wsgi_server_name += ':' + environ['SERVER_PORT'] + + wsgi_server_name = wsgi_server_name.lower() + + if server_name is None: + server_name = wsgi_server_name + else: + server_name = server_name.lower() + + if subdomain is None and not self.host_matching: + cur_server_name = wsgi_server_name.split('.') + real_server_name = server_name.split('.') + offset = -len(real_server_name) + if cur_server_name[offset:] != real_server_name: + # This can happen even with valid configs if the server was + # accesssed directly by IP address under some situations. + # Instead of raising an exception like in Werkzeug 0.7 or + # earlier we go by an invalid subdomain which will result + # in a 404 error on matching. + subdomain = '' + else: + subdomain = '.'.join(filter(None, cur_server_name[:offset])) + + def _get_wsgi_string(name): + val = environ.get(name) + if val is not None: + return wsgi_decoding_dance(val, self.charset) + + script_name = _get_wsgi_string('SCRIPT_NAME') + path_info = _get_wsgi_string('PATH_INFO') + query_args = _get_wsgi_string('QUERY_STRING') + return Map.bind(self, server_name, script_name, + subdomain, environ['wsgi.url_scheme'], + environ['REQUEST_METHOD'], path_info, + query_args=query_args) + + def update(self): + """Called before matching and building to keep the compiled rules + in the correct order after things changed. + """ + if not self._remap: + return + + with self._remap_lock: + if not self._remap: + return + + self._rules.sort(key=lambda x: x.match_compare_key()) + for rules in itervalues(self._rules_by_endpoint): + rules.sort(key=lambda x: x.build_compare_key()) + self._remap = False + + def __repr__(self): + rules = self.iter_rules() + return '%s(%s)' % (self.__class__.__name__, pformat(list(rules))) + + +class MapAdapter(object): + + """Returned by :meth:`Map.bind` or :meth:`Map.bind_to_environ` and does + the URL matching and building based on runtime information. + """ + + def __init__(self, map, server_name, script_name, subdomain, + url_scheme, path_info, default_method, query_args=None): + self.map = map + self.server_name = to_unicode(server_name) + script_name = to_unicode(script_name) + if not script_name.endswith(u'/'): + script_name += u'/' + self.script_name = script_name + self.subdomain = to_unicode(subdomain) + self.url_scheme = to_unicode(url_scheme) + self.path_info = to_unicode(path_info) + self.default_method = to_unicode(default_method) + self.query_args = query_args + + def dispatch(self, view_func, path_info=None, method=None, + catch_http_exceptions=False): + """Does the complete dispatching process. `view_func` is called with + the endpoint and a dict with the values for the view. It should + look up the view function, call it, and return a response object + or WSGI application. http exceptions are not caught by default + so that applications can display nicer error messages by just + catching them by hand. If you want to stick with the default + error messages you can pass it ``catch_http_exceptions=True`` and + it will catch the http exceptions. + + Here a small example for the dispatch usage:: + + from werkzeug.wrappers import Request, Response + from werkzeug.wsgi import responder + from werkzeug.routing import Map, Rule + + def on_index(request): + return Response('Hello from the index') + + url_map = Map([Rule('/', endpoint='index')]) + views = {'index': on_index} + + @responder + def application(environ, start_response): + request = Request(environ) + urls = url_map.bind_to_environ(environ) + return urls.dispatch(lambda e, v: views[e](request, **v), + catch_http_exceptions=True) + + Keep in mind that this method might return exception objects, too, so + use :class:`Response.force_type` to get a response object. + + :param view_func: a function that is called with the endpoint as + first argument and the value dict as second. Has + to dispatch to the actual view function with this + information. (see above) + :param path_info: the path info to use for matching. Overrides the + path info specified on binding. + :param method: the HTTP method used for matching. Overrides the + method specified on binding. + :param catch_http_exceptions: set to `True` to catch any of the + werkzeug :class:`HTTPException`\s. + """ + try: + try: + endpoint, args = self.match(path_info, method) + except RequestRedirect as e: + return e + return view_func(endpoint, args) + except HTTPException as e: + if catch_http_exceptions: + return e + raise + + def match(self, path_info=None, method=None, return_rule=False, + query_args=None): + """The usage is simple: you just pass the match method the current + path info as well as the method (which defaults to `GET`). The + following things can then happen: + + - you receive a `NotFound` exception that indicates that no URL is + matching. A `NotFound` exception is also a WSGI application you + can call to get a default page not found page (happens to be the + same object as `werkzeug.exceptions.NotFound`) + + - you receive a `MethodNotAllowed` exception that indicates that there + is a match for this URL but not for the current request method. + This is useful for RESTful applications. + + - you receive a `RequestRedirect` exception with a `new_url` + attribute. This exception is used to notify you about a request + Werkzeug requests from your WSGI application. This is for example the + case if you request ``/foo`` although the correct URL is ``/foo/`` + You can use the `RequestRedirect` instance as response-like object + similar to all other subclasses of `HTTPException`. + + - you get a tuple in the form ``(endpoint, arguments)`` if there is + a match (unless `return_rule` is True, in which case you get a tuple + in the form ``(rule, arguments)``) + + If the path info is not passed to the match method the default path + info of the map is used (defaults to the root URL if not defined + explicitly). + + All of the exceptions raised are subclasses of `HTTPException` so they + can be used as WSGI responses. They will all render generic error or + redirect pages. + + Here is a small example for matching: + + >>> m = Map([ + ... Rule('/', endpoint='index'), + ... Rule('/downloads/', endpoint='downloads/index'), + ... Rule('/downloads/', endpoint='downloads/show') + ... ]) + >>> urls = m.bind("example.com", "/") + >>> urls.match("/", "GET") + ('index', {}) + >>> urls.match("/downloads/42") + ('downloads/show', {'id': 42}) + + And here is what happens on redirect and missing URLs: + + >>> urls.match("/downloads") + Traceback (most recent call last): + ... + RequestRedirect: http://example.com/downloads/ + >>> urls.match("/missing") + Traceback (most recent call last): + ... + NotFound: 404 Not Found + + :param path_info: the path info to use for matching. Overrides the + path info specified on binding. + :param method: the HTTP method used for matching. Overrides the + method specified on binding. + :param return_rule: return the rule that matched instead of just the + endpoint (defaults to `False`). + :param query_args: optional query arguments that are used for + automatic redirects as string or dictionary. It's + currently not possible to use the query arguments + for URL matching. + + .. versionadded:: 0.6 + `return_rule` was added. + + .. versionadded:: 0.7 + `query_args` was added. + + .. versionchanged:: 0.8 + `query_args` can now also be a string. + """ + self.map.update() + if path_info is None: + path_info = self.path_info + else: + path_info = to_unicode(path_info, self.map.charset) + if query_args is None: + query_args = self.query_args + method = (method or self.default_method).upper() + + path = u'%s|%s' % ( + self.map.host_matching and self.server_name or self.subdomain, + path_info and '/%s' % path_info.lstrip('/') + ) + + have_match_for = set() + for rule in self.map._rules: + try: + rv = rule.match(path, method) + except RequestSlash: + raise RequestRedirect(self.make_redirect_url( + url_quote(path_info, self.map.charset, + safe='/:|+') + '/', query_args)) + except RequestAliasRedirect as e: + raise RequestRedirect(self.make_alias_redirect_url( + path, rule.endpoint, e.matched_values, method, query_args)) + if rv is None: + continue + if rule.methods is not None and method not in rule.methods: + have_match_for.update(rule.methods) + continue + + if self.map.redirect_defaults: + redirect_url = self.get_default_redirect(rule, method, rv, + query_args) + if redirect_url is not None: + raise RequestRedirect(redirect_url) + + if rule.redirect_to is not None: + if isinstance(rule.redirect_to, string_types): + def _handle_match(match): + value = rv[match.group(1)] + return rule._converters[match.group(1)].to_url(value) + redirect_url = _simple_rule_re.sub(_handle_match, + rule.redirect_to) + else: + redirect_url = rule.redirect_to(self, **rv) + raise RequestRedirect(str(url_join('%s://%s%s%s' % ( + self.url_scheme or 'http', + self.subdomain and self.subdomain + '.' or '', + self.server_name, + self.script_name + ), redirect_url))) + + if return_rule: + return rule, rv + else: + return rule.endpoint, rv + + if have_match_for: + raise MethodNotAllowed(valid_methods=list(have_match_for)) + raise NotFound() + + def test(self, path_info=None, method=None): + """Test if a rule would match. Works like `match` but returns `True` + if the URL matches, or `False` if it does not exist. + + :param path_info: the path info to use for matching. Overrides the + path info specified on binding. + :param method: the HTTP method used for matching. Overrides the + method specified on binding. + """ + try: + self.match(path_info, method) + except RequestRedirect: + pass + except HTTPException: + return False + return True + + def allowed_methods(self, path_info=None): + """Returns the valid methods that match for a given path. + + .. versionadded:: 0.7 + """ + try: + self.match(path_info, method='--') + except MethodNotAllowed as e: + return e.valid_methods + except HTTPException as e: + pass + return [] + + def get_host(self, domain_part): + """Figures out the full host name for the given domain part. The + domain part is a subdomain in case host matching is disabled or + a full host name. + """ + if self.map.host_matching: + if domain_part is None: + return self.server_name + return to_unicode(domain_part, 'ascii') + subdomain = domain_part + if subdomain is None: + subdomain = self.subdomain + else: + subdomain = to_unicode(subdomain, 'ascii') + return (subdomain and subdomain + u'.' or u'') + self.server_name + + def get_default_redirect(self, rule, method, values, query_args): + """A helper that returns the URL to redirect to if it finds one. + This is used for default redirecting only. + + :internal: + """ + assert self.map.redirect_defaults + for r in self.map._rules_by_endpoint[rule.endpoint]: + # every rule that comes after this one, including ourself + # has a lower priority for the defaults. We order the ones + # with the highest priority up for building. + if r is rule: + break + if r.provides_defaults_for(rule) and \ + r.suitable_for(values, method): + values.update(r.defaults) + domain_part, path = r.build(values) + return self.make_redirect_url( + path, query_args, domain_part=domain_part) + + def encode_query_args(self, query_args): + if not isinstance(query_args, string_types): + query_args = url_encode(query_args, self.map.charset) + return query_args + + def make_redirect_url(self, path_info, query_args=None, domain_part=None): + """Creates a redirect URL. + + :internal: + """ + suffix = '' + if query_args: + suffix = '?' + self.encode_query_args(query_args) + return str('%s://%s/%s%s' % ( + self.url_scheme or 'http', + self.get_host(domain_part), + posixpath.join(self.script_name[:-1].lstrip('/'), + path_info.lstrip('/')), + suffix + )) + + def make_alias_redirect_url(self, path, endpoint, values, method, query_args): + """Internally called to make an alias redirect URL.""" + url = self.build(endpoint, values, method, append_unknown=False, + force_external=True) + if query_args: + url += '?' + self.encode_query_args(query_args) + assert url != path, 'detected invalid alias setting. No canonical ' \ + 'URL found' + return url + + def _partial_build(self, endpoint, values, method, append_unknown): + """Helper for :meth:`build`. Returns subdomain and path for the + rule that accepts this endpoint, values and method. + + :internal: + """ + # in case the method is none, try with the default method first + if method is None: + rv = self._partial_build(endpoint, values, self.default_method, + append_unknown) + if rv is not None: + return rv + + # default method did not match or a specific method is passed, + # check all and go with first result. + for rule in self.map._rules_by_endpoint.get(endpoint, ()): + if rule.suitable_for(values, method): + rv = rule.build(values, append_unknown) + if rv is not None: + return rv + + def build(self, endpoint, values=None, method=None, force_external=False, + append_unknown=True): + """Building URLs works pretty much the other way round. Instead of + `match` you call `build` and pass it the endpoint and a dict of + arguments for the placeholders. + + The `build` function also accepts an argument called `force_external` + which, if you set it to `True` will force external URLs. Per default + external URLs (include the server name) will only be used if the + target URL is on a different subdomain. + + >>> m = Map([ + ... Rule('/', endpoint='index'), + ... Rule('/downloads/', endpoint='downloads/index'), + ... Rule('/downloads/', endpoint='downloads/show') + ... ]) + >>> urls = m.bind("example.com", "/") + >>> urls.build("index", {}) + '/' + >>> urls.build("downloads/show", {'id': 42}) + '/downloads/42' + >>> urls.build("downloads/show", {'id': 42}, force_external=True) + 'http://example.com/downloads/42' + + Because URLs cannot contain non ASCII data you will always get + bytestrings back. Non ASCII characters are urlencoded with the + charset defined on the map instance. + + Additional values are converted to unicode and appended to the URL as + URL querystring parameters: + + >>> urls.build("index", {'q': 'My Searchstring'}) + '/?q=My+Searchstring' + + When processing those additional values, lists are furthermore + interpreted as multiple values (as per + :py:class:`werkzeug.datastructures.MultiDict`): + + >>> urls.build("index", {'q': ['a', 'b', 'c']}) + '/?q=a&q=b&q=c' + + If a rule does not exist when building a `BuildError` exception is + raised. + + The build method accepts an argument called `method` which allows you + to specify the method you want to have an URL built for if you have + different methods for the same endpoint specified. + + .. versionadded:: 0.6 + the `append_unknown` parameter was added. + + :param endpoint: the endpoint of the URL to build. + :param values: the values for the URL to build. Unhandled values are + appended to the URL as query parameters. + :param method: the HTTP method for the rule if there are different + URLs for different methods on the same endpoint. + :param force_external: enforce full canonical external URLs. If the URL + scheme is not provided, this will generate + a protocol-relative URL. + :param append_unknown: unknown parameters are appended to the generated + URL as query string argument. Disable this + if you want the builder to ignore those. + """ + self.map.update() + if values: + if isinstance(values, MultiDict): + valueiter = iteritems(values, multi=True) + else: + valueiter = iteritems(values) + values = dict((k, v) for k, v in valueiter if v is not None) + else: + values = {} + + rv = self._partial_build(endpoint, values, method, append_unknown) + if rv is None: + raise BuildError(endpoint, values, method, self) + domain_part, path = rv + + host = self.get_host(domain_part) + + # shortcut this. + if not force_external and ( + (self.map.host_matching and host == self.server_name) or + (not self.map.host_matching and domain_part == self.subdomain) + ): + return str(url_join(self.script_name, './' + path.lstrip('/'))) + return str('%s//%s%s/%s' % ( + self.url_scheme + ':' if self.url_scheme else '', + host, + self.script_name[:-1], + path.lstrip('/') + )) diff --git a/pyextra/werkzeug/security.py b/pyextra/werkzeug/security.py new file mode 100644 index 00000000000000..d4c5c9f487b8ce --- /dev/null +++ b/pyextra/werkzeug/security.py @@ -0,0 +1,270 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.security + ~~~~~~~~~~~~~~~~~ + + Security related helpers such as secure password hashing tools. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import os +import hmac +import hashlib +import posixpath +import codecs +from struct import Struct +from random import SystemRandom +from operator import xor +from itertools import starmap + +from werkzeug._compat import range_type, PY2, text_type, izip, to_bytes, \ + string_types, to_native + + +SALT_CHARS = 'abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789' +DEFAULT_PBKDF2_ITERATIONS = 50000 + + +_pack_int = Struct('>I').pack +_builtin_safe_str_cmp = getattr(hmac, 'compare_digest', None) +_sys_rng = SystemRandom() +_os_alt_seps = list(sep for sep in [os.path.sep, os.path.altsep] + if sep not in (None, '/')) + + +def _find_hashlib_algorithms(): + algos = getattr(hashlib, 'algorithms', None) + if algos is None: + algos = ('md5', 'sha1', 'sha224', 'sha256', 'sha384', 'sha512') + rv = {} + for algo in algos: + func = getattr(hashlib, algo, None) + if func is not None: + rv[algo] = func + return rv +_hash_funcs = _find_hashlib_algorithms() + + +def pbkdf2_hex(data, salt, iterations=DEFAULT_PBKDF2_ITERATIONS, + keylen=None, hashfunc=None): + """Like :func:`pbkdf2_bin`, but returns a hex-encoded string. + + .. versionadded:: 0.9 + + :param data: the data to derive. + :param salt: the salt for the derivation. + :param iterations: the number of iterations. + :param keylen: the length of the resulting key. If not provided, + the digest size will be used. + :param hashfunc: the hash function to use. This can either be the + string name of a known hash function, or a function + from the hashlib module. Defaults to sha256. + """ + rv = pbkdf2_bin(data, salt, iterations, keylen, hashfunc) + return to_native(codecs.encode(rv, 'hex_codec')) + + +_has_native_pbkdf2 = hasattr(hashlib, 'pbkdf2_hmac') + + +def pbkdf2_bin(data, salt, iterations=DEFAULT_PBKDF2_ITERATIONS, + keylen=None, hashfunc=None): + """Returns a binary digest for the PBKDF2 hash algorithm of `data` + with the given `salt`. It iterates `iterations` times and produces a + key of `keylen` bytes. By default, SHA-256 is used as hash function; + a different hashlib `hashfunc` can be provided. + + .. versionadded:: 0.9 + + :param data: the data to derive. + :param salt: the salt for the derivation. + :param iterations: the number of iterations. + :param keylen: the length of the resulting key. If not provided + the digest size will be used. + :param hashfunc: the hash function to use. This can either be the + string name of a known hash function or a function + from the hashlib module. Defaults to sha256. + """ + if isinstance(hashfunc, string_types): + hashfunc = _hash_funcs[hashfunc] + elif not hashfunc: + hashfunc = hashlib.sha256 + data = to_bytes(data) + salt = to_bytes(salt) + + # If we're on Python with pbkdf2_hmac we can try to use it for + # compatible digests. + if _has_native_pbkdf2: + _test_hash = hashfunc() + if hasattr(_test_hash, 'name') and \ + _test_hash.name in _hash_funcs: + return hashlib.pbkdf2_hmac(_test_hash.name, + data, salt, iterations, + keylen) + + mac = hmac.HMAC(data, None, hashfunc) + if not keylen: + keylen = mac.digest_size + + def _pseudorandom(x, mac=mac): + h = mac.copy() + h.update(x) + return bytearray(h.digest()) + buf = bytearray() + for block in range_type(1, -(-keylen // mac.digest_size) + 1): + rv = u = _pseudorandom(salt + _pack_int(block)) + for i in range_type(iterations - 1): + u = _pseudorandom(bytes(u)) + rv = bytearray(starmap(xor, izip(rv, u))) + buf.extend(rv) + return bytes(buf[:keylen]) + + +def safe_str_cmp(a, b): + """This function compares strings in somewhat constant time. This + requires that the length of at least one string is known in advance. + + Returns `True` if the two strings are equal, or `False` if they are not. + + .. versionadded:: 0.7 + """ + if isinstance(a, text_type): + a = a.encode('utf-8') + if isinstance(b, text_type): + b = b.encode('utf-8') + + if _builtin_safe_str_cmp is not None: + return _builtin_safe_str_cmp(a, b) + + if len(a) != len(b): + return False + + rv = 0 + if PY2: + for x, y in izip(a, b): + rv |= ord(x) ^ ord(y) + else: + for x, y in izip(a, b): + rv |= x ^ y + + return rv == 0 + + +def gen_salt(length): + """Generate a random string of SALT_CHARS with specified ``length``.""" + if length <= 0: + raise ValueError('Salt length must be positive') + return ''.join(_sys_rng.choice(SALT_CHARS) for _ in range_type(length)) + + +def _hash_internal(method, salt, password): + """Internal password hash helper. Supports plaintext without salt, + unsalted and salted passwords. In case salted passwords are used + hmac is used. + """ + if method == 'plain': + return password, method + + if isinstance(password, text_type): + password = password.encode('utf-8') + + if method.startswith('pbkdf2:'): + args = method[7:].split(':') + if len(args) not in (1, 2): + raise ValueError('Invalid number of arguments for PBKDF2') + method = args.pop(0) + iterations = args and int(args[0] or 0) or DEFAULT_PBKDF2_ITERATIONS + is_pbkdf2 = True + actual_method = 'pbkdf2:%s:%d' % (method, iterations) + else: + is_pbkdf2 = False + actual_method = method + + hash_func = _hash_funcs.get(method) + if hash_func is None: + raise TypeError('invalid method %r' % method) + + if is_pbkdf2: + if not salt: + raise ValueError('Salt is required for PBKDF2') + rv = pbkdf2_hex(password, salt, iterations, + hashfunc=hash_func) + elif salt: + if isinstance(salt, text_type): + salt = salt.encode('utf-8') + rv = hmac.HMAC(salt, password, hash_func).hexdigest() + else: + h = hash_func() + h.update(password) + rv = h.hexdigest() + return rv, actual_method + + +def generate_password_hash(password, method='pbkdf2:sha256', salt_length=8): + """Hash a password with the given method and salt with a string of + the given length. The format of the string returned includes the method + that was used so that :func:`check_password_hash` can check the hash. + + The format for the hashed string looks like this:: + + method$salt$hash + + This method can **not** generate unsalted passwords but it is possible + to set param method='plain' in order to enforce plaintext passwords. + If a salt is used, hmac is used internally to salt the password. + + If PBKDF2 is wanted it can be enabled by setting the method to + ``pbkdf2:method:iterations`` where iterations is optional:: + + pbkdf2:sha256:80000$salt$hash + pbkdf2:sha256$salt$hash + + :param password: the password to hash. + :param method: the hash method to use (one that hashlib supports). Can + optionally be in the format ``pbkdf2:[:iterations]`` + to enable PBKDF2. + :param salt_length: the length of the salt in letters. + """ + salt = method != 'plain' and gen_salt(salt_length) or '' + h, actual_method = _hash_internal(method, salt, password) + return '%s$%s$%s' % (actual_method, salt, h) + + +def check_password_hash(pwhash, password): + """check a password against a given salted and hashed password value. + In order to support unsalted legacy passwords this method supports + plain text passwords, md5 and sha1 hashes (both salted and unsalted). + + Returns `True` if the password matched, `False` otherwise. + + :param pwhash: a hashed string like returned by + :func:`generate_password_hash`. + :param password: the plaintext password to compare against the hash. + """ + if pwhash.count('$') < 2: + return False + method, salt, hashval = pwhash.split('$', 2) + return safe_str_cmp(_hash_internal(method, salt, password)[0], hashval) + + +def safe_join(directory, *pathnames): + """Safely join `directory` and one or more untrusted `pathnames`. If this + cannot be done, this function returns ``None``. + + :param directory: the base directory. + :param pathnames: the untrusted pathnames relative to that directory. + """ + parts = [directory] + for filename in pathnames: + if filename != '': + filename = posixpath.normpath(filename) + for sep in _os_alt_seps: + if sep in filename: + return None + if os.path.isabs(filename) or \ + filename == '..' or \ + filename.startswith('../'): + return None + parts.append(filename) + return posixpath.join(*parts) diff --git a/pyextra/werkzeug/serving.py b/pyextra/werkzeug/serving.py new file mode 100644 index 00000000000000..902f1aa1c62d3a --- /dev/null +++ b/pyextra/werkzeug/serving.py @@ -0,0 +1,862 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.serving + ~~~~~~~~~~~~~~~~ + + There are many ways to serve a WSGI application. While you're developing + it you usually don't want a full blown webserver like Apache but a simple + standalone one. From Python 2.5 onwards there is the `wsgiref`_ server in + the standard library. If you're using older versions of Python you can + download the package from the cheeseshop. + + However there are some caveats. Sourcecode won't reload itself when + changed and each time you kill the server using ``^C`` you get an + `KeyboardInterrupt` error. While the latter is easy to solve the first + one can be a pain in the ass in some situations. + + The easiest way is creating a small ``start-myproject.py`` that runs the + application:: + + #!/usr/bin/env python + # -*- coding: utf-8 -*- + from myproject import make_app + from werkzeug.serving import run_simple + + app = make_app(...) + run_simple('localhost', 8080, app, use_reloader=True) + + You can also pass it a `extra_files` keyword argument with a list of + additional files (like configuration files) you want to observe. + + For bigger applications you should consider using `click` + (http://click.pocoo.org) instead of a simple start file. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +from __future__ import with_statement + +import io +import os +import socket +import sys +import signal + + +can_fork = hasattr(os, "fork") + + +try: + import termcolor +except ImportError: + termcolor = None + +try: + import ssl +except ImportError: + class _SslDummy(object): + def __getattr__(self, name): + raise RuntimeError('SSL support unavailable') + ssl = _SslDummy() + + +def _get_openssl_crypto_module(): + try: + from OpenSSL import crypto + except ImportError: + raise TypeError('Using ad-hoc certificates requires the pyOpenSSL ' + 'library.') + else: + return crypto + + +try: + import SocketServer as socketserver + from BaseHTTPServer import HTTPServer, BaseHTTPRequestHandler +except ImportError: + import socketserver + from http.server import HTTPServer, BaseHTTPRequestHandler + +ThreadingMixIn = socketserver.ThreadingMixIn + +if can_fork: + ForkingMixIn = socketserver.ForkingMixIn +else: + class ForkingMixIn(object): + pass + +# important: do not use relative imports here or python -m will break +import werkzeug +from werkzeug._internal import _log +from werkzeug._compat import PY2, WIN, reraise, wsgi_encoding_dance +from werkzeug.urls import url_parse, url_unquote +from werkzeug.exceptions import InternalServerError + + +LISTEN_QUEUE = 128 +can_open_by_fd = not WIN and hasattr(socket, 'fromfd') + + +class DechunkedInput(io.RawIOBase): + """An input stream that handles Transfer-Encoding 'chunked'""" + + def __init__(self, rfile): + self._rfile = rfile + self._done = False + self._len = 0 + + def readable(self): + return True + + def read_chunk_len(self): + try: + line = self._rfile.readline().decode('latin1') + _len = int(line.strip(), 16) + except ValueError: + raise IOError('Invalid chunk header') + if _len < 0: + raise IOError('Negative chunk length not allowed') + return _len + + def readinto(self, buf): + read = 0 + while not self._done and read < len(buf): + if self._len == 0: + # This is the first chunk or we fully consumed the previous + # one. Read the next length of the next chunk + self._len = self.read_chunk_len() + + if self._len == 0: + # Found the final chunk of size 0. The stream is now exhausted, + # but there is still a final newline that should be consumed + self._done = True + + if self._len > 0: + # There is data (left) in this chunk, so append it to the + # buffer. If this operation fully consumes the chunk, this will + # reset self._len to 0. + n = min(len(buf), self._len) + buf[read:read + n] = self._rfile.read(n) + self._len -= n + read += n + + if self._len == 0: + # Skip the terminating newline of a chunk that has been fully + # consumed. This also applies to the 0-sized final chunk + terminator = self._rfile.readline() + if terminator not in (b'\n', b'\r\n', b'\r'): + raise IOError('Missing chunk terminating newline') + + return read + + +class WSGIRequestHandler(BaseHTTPRequestHandler, object): + + """A request handler that implements WSGI dispatching.""" + + @property + def server_version(self): + return 'Werkzeug/' + werkzeug.__version__ + + def make_environ(self): + request_url = url_parse(self.path) + + def shutdown_server(): + self.server.shutdown_signal = True + + url_scheme = self.server.ssl_context is None and 'http' or 'https' + path_info = url_unquote(request_url.path) + + environ = { + 'wsgi.version': (1, 0), + 'wsgi.url_scheme': url_scheme, + 'wsgi.input': self.rfile, + 'wsgi.errors': sys.stderr, + 'wsgi.multithread': self.server.multithread, + 'wsgi.multiprocess': self.server.multiprocess, + 'wsgi.run_once': False, + 'werkzeug.server.shutdown': shutdown_server, + 'SERVER_SOFTWARE': self.server_version, + 'REQUEST_METHOD': self.command, + 'SCRIPT_NAME': '', + 'PATH_INFO': wsgi_encoding_dance(path_info), + 'QUERY_STRING': wsgi_encoding_dance(request_url.query), + 'REMOTE_ADDR': self.address_string(), + 'REMOTE_PORT': self.port_integer(), + 'SERVER_NAME': self.server.server_address[0], + 'SERVER_PORT': str(self.server.server_address[1]), + 'SERVER_PROTOCOL': self.request_version + } + + for key, value in self.headers.items(): + key = key.upper().replace('-', '_') + if key not in ('CONTENT_TYPE', 'CONTENT_LENGTH'): + key = 'HTTP_' + key + environ[key] = value + + if environ.get('HTTP_TRANSFER_ENCODING', '').strip().lower() == 'chunked': + environ['wsgi.input_terminated'] = True + environ['wsgi.input'] = DechunkedInput(environ['wsgi.input']) + + if request_url.scheme and request_url.netloc: + environ['HTTP_HOST'] = request_url.netloc + + return environ + + def run_wsgi(self): + if self.headers.get('Expect', '').lower().strip() == '100-continue': + self.wfile.write(b'HTTP/1.1 100 Continue\r\n\r\n') + + self.environ = environ = self.make_environ() + headers_set = [] + headers_sent = [] + + def write(data): + assert headers_set, 'write() before start_response' + if not headers_sent: + status, response_headers = headers_sent[:] = headers_set + try: + code, msg = status.split(None, 1) + except ValueError: + code, msg = status, "" + code = int(code) + self.send_response(code, msg) + header_keys = set() + for key, value in response_headers: + self.send_header(key, value) + key = key.lower() + header_keys.add(key) + if not ('content-length' in header_keys or + environ['REQUEST_METHOD'] == 'HEAD' or + code < 200 or code in (204, 304)): + self.close_connection = True + self.send_header('Connection', 'close') + if 'server' not in header_keys: + self.send_header('Server', self.version_string()) + if 'date' not in header_keys: + self.send_header('Date', self.date_time_string()) + self.end_headers() + + assert isinstance(data, bytes), 'applications must write bytes' + self.wfile.write(data) + self.wfile.flush() + + def start_response(status, response_headers, exc_info=None): + if exc_info: + try: + if headers_sent: + reraise(*exc_info) + finally: + exc_info = None + elif headers_set: + raise AssertionError('Headers already set') + headers_set[:] = [status, response_headers] + return write + + def execute(app): + application_iter = app(environ, start_response) + try: + for data in application_iter: + write(data) + if not headers_sent: + write(b'') + finally: + if hasattr(application_iter, 'close'): + application_iter.close() + application_iter = None + + try: + execute(self.server.app) + except (socket.error, socket.timeout) as e: + self.connection_dropped(e, environ) + except Exception: + if self.server.passthrough_errors: + raise + from werkzeug.debug.tbtools import get_current_traceback + traceback = get_current_traceback(ignore_system_exceptions=True) + try: + # if we haven't yet sent the headers but they are set + # we roll back to be able to set them again. + if not headers_sent: + del headers_set[:] + execute(InternalServerError()) + except Exception: + pass + self.server.log('error', 'Error on request:\n%s', + traceback.plaintext) + + def handle(self): + """Handles a request ignoring dropped connections.""" + rv = None + try: + rv = BaseHTTPRequestHandler.handle(self) + except (socket.error, socket.timeout) as e: + self.connection_dropped(e) + except Exception: + if self.server.ssl_context is None or not is_ssl_error(): + raise + if self.server.shutdown_signal: + self.initiate_shutdown() + return rv + + def initiate_shutdown(self): + """A horrible, horrible way to kill the server for Python 2.6 and + later. It's the best we can do. + """ + # Windows does not provide SIGKILL, go with SIGTERM then. + sig = getattr(signal, 'SIGKILL', signal.SIGTERM) + # reloader active + if os.environ.get('WERKZEUG_RUN_MAIN') == 'true': + os.kill(os.getpid(), sig) + # python 2.7 + self.server._BaseServer__shutdown_request = True + # python 2.6 + self.server._BaseServer__serving = False + + def connection_dropped(self, error, environ=None): + """Called if the connection was closed by the client. By default + nothing happens. + """ + + def handle_one_request(self): + """Handle a single HTTP request.""" + self.raw_requestline = self.rfile.readline() + if not self.raw_requestline: + self.close_connection = 1 + elif self.parse_request(): + return self.run_wsgi() + + def send_response(self, code, message=None): + """Send the response header and log the response code.""" + self.log_request(code) + if message is None: + message = code in self.responses and self.responses[code][0] or '' + if self.request_version != 'HTTP/0.9': + hdr = "%s %d %s\r\n" % (self.protocol_version, code, message) + self.wfile.write(hdr.encode('ascii')) + + def version_string(self): + return BaseHTTPRequestHandler.version_string(self).strip() + + def address_string(self): + if getattr(self, 'environ', None): + return self.environ['REMOTE_ADDR'] + else: + return self.client_address[0] + + def port_integer(self): + return self.client_address[1] + + def log_request(self, code='-', size='-'): + msg = self.requestline + code = str(code) + + if termcolor: + color = termcolor.colored + + if code[0] == '1': # 1xx - Informational + msg = color(msg, attrs=['bold']) + elif code[0] == '2': # 2xx - Success + msg = color(msg, color='white') + elif code == '304': # 304 - Resource Not Modified + msg = color(msg, color='cyan') + elif code[0] == '3': # 3xx - Redirection + msg = color(msg, color='green') + elif code == '404': # 404 - Resource Not Found + msg = color(msg, color='yellow') + elif code[0] == '4': # 4xx - Client Error + msg = color(msg, color='red', attrs=['bold']) + else: # 5xx, or any other response + msg = color(msg, color='magenta', attrs=['bold']) + + self.log('info', '"%s" %s %s', msg, code, size) + + def log_error(self, *args): + self.log('error', *args) + + def log_message(self, format, *args): + self.log('info', format, *args) + + def log(self, type, message, *args): + _log(type, '%s - - [%s] %s\n' % (self.address_string(), + self.log_date_time_string(), + message % args)) + + +#: backwards compatible name if someone is subclassing it +BaseRequestHandler = WSGIRequestHandler + + +def generate_adhoc_ssl_pair(cn=None): + from random import random + crypto = _get_openssl_crypto_module() + + # pretty damn sure that this is not actually accepted by anyone + if cn is None: + cn = '*' + + cert = crypto.X509() + cert.set_serial_number(int(random() * sys.maxsize)) + cert.gmtime_adj_notBefore(0) + cert.gmtime_adj_notAfter(60 * 60 * 24 * 365) + + subject = cert.get_subject() + subject.CN = cn + subject.O = 'Dummy Certificate' # noqa: E741 + + issuer = cert.get_issuer() + issuer.CN = 'Untrusted Authority' + issuer.O = 'Self-Signed' # noqa: E741 + + pkey = crypto.PKey() + pkey.generate_key(crypto.TYPE_RSA, 2048) + cert.set_pubkey(pkey) + cert.sign(pkey, 'sha256') + + return cert, pkey + + +def make_ssl_devcert(base_path, host=None, cn=None): + """Creates an SSL key for development. This should be used instead of + the ``'adhoc'`` key which generates a new cert on each server start. + It accepts a path for where it should store the key and cert and + either a host or CN. If a host is given it will use the CN + ``*.host/CN=host``. + + For more information see :func:`run_simple`. + + .. versionadded:: 0.9 + + :param base_path: the path to the certificate and key. The extension + ``.crt`` is added for the certificate, ``.key`` is + added for the key. + :param host: the name of the host. This can be used as an alternative + for the `cn`. + :param cn: the `CN` to use. + """ + from OpenSSL import crypto + if host is not None: + cn = '*.%s/CN=%s' % (host, host) + cert, pkey = generate_adhoc_ssl_pair(cn=cn) + + cert_file = base_path + '.crt' + pkey_file = base_path + '.key' + + with open(cert_file, 'wb') as f: + f.write(crypto.dump_certificate(crypto.FILETYPE_PEM, cert)) + with open(pkey_file, 'wb') as f: + f.write(crypto.dump_privatekey(crypto.FILETYPE_PEM, pkey)) + + return cert_file, pkey_file + + +def generate_adhoc_ssl_context(): + """Generates an adhoc SSL context for the development server.""" + crypto = _get_openssl_crypto_module() + import tempfile + import atexit + + cert, pkey = generate_adhoc_ssl_pair() + cert_handle, cert_file = tempfile.mkstemp() + pkey_handle, pkey_file = tempfile.mkstemp() + atexit.register(os.remove, pkey_file) + atexit.register(os.remove, cert_file) + + os.write(cert_handle, crypto.dump_certificate(crypto.FILETYPE_PEM, cert)) + os.write(pkey_handle, crypto.dump_privatekey(crypto.FILETYPE_PEM, pkey)) + os.close(cert_handle) + os.close(pkey_handle) + ctx = load_ssl_context(cert_file, pkey_file) + return ctx + + +def load_ssl_context(cert_file, pkey_file=None, protocol=None): + """Loads SSL context from cert/private key files and optional protocol. + Many parameters are directly taken from the API of + :py:class:`ssl.SSLContext`. + + :param cert_file: Path of the certificate to use. + :param pkey_file: Path of the private key to use. If not given, the key + will be obtained from the certificate file. + :param protocol: One of the ``PROTOCOL_*`` constants in the stdlib ``ssl`` + module. Defaults to ``PROTOCOL_SSLv23``. + """ + if protocol is None: + protocol = ssl.PROTOCOL_SSLv23 + ctx = _SSLContext(protocol) + ctx.load_cert_chain(cert_file, pkey_file) + return ctx + + +class _SSLContext(object): + + '''A dummy class with a small subset of Python3's ``ssl.SSLContext``, only + intended to be used with and by Werkzeug.''' + + def __init__(self, protocol): + self._protocol = protocol + self._certfile = None + self._keyfile = None + self._password = None + + def load_cert_chain(self, certfile, keyfile=None, password=None): + self._certfile = certfile + self._keyfile = keyfile or certfile + self._password = password + + def wrap_socket(self, sock, **kwargs): + return ssl.wrap_socket(sock, keyfile=self._keyfile, + certfile=self._certfile, + ssl_version=self._protocol, **kwargs) + + +def is_ssl_error(error=None): + """Checks if the given error (or the current one) is an SSL error.""" + exc_types = (ssl.SSLError,) + try: + from OpenSSL.SSL import Error + exc_types += (Error,) + except ImportError: + pass + + if error is None: + error = sys.exc_info()[1] + return isinstance(error, exc_types) + + +def select_ip_version(host, port): + """Returns AF_INET4 or AF_INET6 depending on where to connect to.""" + # disabled due to problems with current ipv6 implementations + # and various operating systems. Probably this code also is + # not supposed to work, but I can't come up with any other + # ways to implement this. + # try: + # info = socket.getaddrinfo(host, port, socket.AF_UNSPEC, + # socket.SOCK_STREAM, 0, + # socket.AI_PASSIVE) + # if info: + # return info[0][0] + # except socket.gaierror: + # pass + if ':' in host and hasattr(socket, 'AF_INET6'): + return socket.AF_INET6 + return socket.AF_INET + + +def get_sockaddr(host, port, family): + """Returns a fully qualified socket address, that can properly used by + socket.bind""" + try: + res = socket.getaddrinfo(host, port, family, + socket.SOCK_STREAM, socket.SOL_TCP) + except socket.gaierror: + return (host, port) + return res[0][4] + + +class BaseWSGIServer(HTTPServer, object): + + """Simple single-threaded, single-process WSGI server.""" + multithread = False + multiprocess = False + request_queue_size = LISTEN_QUEUE + + def __init__(self, host, port, app, handler=None, + passthrough_errors=False, ssl_context=None, fd=None): + if handler is None: + handler = WSGIRequestHandler + + self.address_family = select_ip_version(host, port) + + if fd is not None: + real_sock = socket.fromfd(fd, self.address_family, + socket.SOCK_STREAM) + port = 0 + HTTPServer.__init__(self, get_sockaddr(host, int(port), + self.address_family), handler) + self.app = app + self.passthrough_errors = passthrough_errors + self.shutdown_signal = False + self.host = host + self.port = self.socket.getsockname()[1] + + # Patch in the original socket. + if fd is not None: + self.socket.close() + self.socket = real_sock + self.server_address = self.socket.getsockname() + + if ssl_context is not None: + if isinstance(ssl_context, tuple): + ssl_context = load_ssl_context(*ssl_context) + if ssl_context == 'adhoc': + ssl_context = generate_adhoc_ssl_context() + # If we are on Python 2 the return value from socket.fromfd + # is an internal socket object but what we need for ssl wrap + # is the wrapper around it :( + sock = self.socket + if PY2 and not isinstance(sock, socket.socket): + sock = socket.socket(sock.family, sock.type, sock.proto, sock) + self.socket = ssl_context.wrap_socket(sock, server_side=True) + self.ssl_context = ssl_context + else: + self.ssl_context = None + + def log(self, type, message, *args): + _log(type, message, *args) + + def serve_forever(self): + self.shutdown_signal = False + try: + HTTPServer.serve_forever(self) + except KeyboardInterrupt: + pass + finally: + self.server_close() + + def handle_error(self, request, client_address): + if self.passthrough_errors: + raise + return HTTPServer.handle_error(self, request, client_address) + + def get_request(self): + con, info = self.socket.accept() + return con, info + + +class ThreadedWSGIServer(ThreadingMixIn, BaseWSGIServer): + + """A WSGI server that does threading.""" + multithread = True + daemon_threads = True + + +class ForkingWSGIServer(ForkingMixIn, BaseWSGIServer): + + """A WSGI server that does forking.""" + multiprocess = True + + def __init__(self, host, port, app, processes=40, handler=None, + passthrough_errors=False, ssl_context=None, fd=None): + if not can_fork: + raise ValueError('Your platform does not support forking.') + BaseWSGIServer.__init__(self, host, port, app, handler, + passthrough_errors, ssl_context, fd) + self.max_children = processes + + +def make_server(host=None, port=None, app=None, threaded=False, processes=1, + request_handler=None, passthrough_errors=False, + ssl_context=None, fd=None): + """Create a new server instance that is either threaded, or forks + or just processes one request after another. + """ + if threaded and processes > 1: + raise ValueError("cannot have a multithreaded and " + "multi process server.") + elif threaded: + return ThreadedWSGIServer(host, port, app, request_handler, + passthrough_errors, ssl_context, fd=fd) + elif processes > 1: + return ForkingWSGIServer(host, port, app, processes, request_handler, + passthrough_errors, ssl_context, fd=fd) + else: + return BaseWSGIServer(host, port, app, request_handler, + passthrough_errors, ssl_context, fd=fd) + + +def is_running_from_reloader(): + """Checks if the application is running from within the Werkzeug + reloader subprocess. + + .. versionadded:: 0.10 + """ + return os.environ.get('WERKZEUG_RUN_MAIN') == 'true' + + +def run_simple(hostname, port, application, use_reloader=False, + use_debugger=False, use_evalex=True, + extra_files=None, reloader_interval=1, + reloader_type='auto', threaded=False, + processes=1, request_handler=None, static_files=None, + passthrough_errors=False, ssl_context=None): + """Start a WSGI application. Optional features include a reloader, + multithreading and fork support. + + This function has a command-line interface too:: + + python -m werkzeug.serving --help + + .. versionadded:: 0.5 + `static_files` was added to simplify serving of static files as well + as `passthrough_errors`. + + .. versionadded:: 0.6 + support for SSL was added. + + .. versionadded:: 0.8 + Added support for automatically loading a SSL context from certificate + file and private key. + + .. versionadded:: 0.9 + Added command-line interface. + + .. versionadded:: 0.10 + Improved the reloader and added support for changing the backend + through the `reloader_type` parameter. See :ref:`reloader` + for more information. + + :param hostname: The host for the application. eg: ``'localhost'`` + :param port: The port for the server. eg: ``8080`` + :param application: the WSGI application to execute + :param use_reloader: should the server automatically restart the python + process if modules were changed? + :param use_debugger: should the werkzeug debugging system be used? + :param use_evalex: should the exception evaluation feature be enabled? + :param extra_files: a list of files the reloader should watch + additionally to the modules. For example configuration + files. + :param reloader_interval: the interval for the reloader in seconds. + :param reloader_type: the type of reloader to use. The default is + auto detection. Valid values are ``'stat'`` and + ``'watchdog'``. See :ref:`reloader` for more + information. + :param threaded: should the process handle each request in a separate + thread? + :param processes: if greater than 1 then handle each request in a new process + up to this maximum number of concurrent processes. + :param request_handler: optional parameter that can be used to replace + the default one. You can use this to replace it + with a different + :class:`~BaseHTTPServer.BaseHTTPRequestHandler` + subclass. + :param static_files: a list or dict of paths for static files. This works + exactly like :class:`SharedDataMiddleware`, it's actually + just wrapping the application in that middleware before + serving. + :param passthrough_errors: set this to `True` to disable the error catching. + This means that the server will die on errors but + it can be useful to hook debuggers in (pdb etc.) + :param ssl_context: an SSL context for the connection. Either an + :class:`ssl.SSLContext`, a tuple in the form + ``(cert_file, pkey_file)``, the string ``'adhoc'`` if + the server should automatically create one, or ``None`` + to disable SSL (which is the default). + """ + if not isinstance(port, int): + raise TypeError('port must be an integer') + if use_debugger: + from werkzeug.debug import DebuggedApplication + application = DebuggedApplication(application, use_evalex) + if static_files: + from werkzeug.wsgi import SharedDataMiddleware + application = SharedDataMiddleware(application, static_files) + + def log_startup(sock): + display_hostname = hostname not in ('', '*') and hostname or 'localhost' + if ':' in display_hostname: + display_hostname = '[%s]' % display_hostname + quit_msg = '(Press CTRL+C to quit)' + port = sock.getsockname()[1] + _log('info', ' * Running on %s://%s:%d/ %s', + ssl_context is None and 'http' or 'https', + display_hostname, port, quit_msg) + + def inner(): + try: + fd = int(os.environ['WERKZEUG_SERVER_FD']) + except (LookupError, ValueError): + fd = None + srv = make_server(hostname, port, application, threaded, + processes, request_handler, + passthrough_errors, ssl_context, + fd=fd) + if fd is None: + log_startup(srv.socket) + srv.serve_forever() + + if use_reloader: + # If we're not running already in the subprocess that is the + # reloader we want to open up a socket early to make sure the + # port is actually available. + if os.environ.get('WERKZEUG_RUN_MAIN') != 'true': + if port == 0 and not can_open_by_fd: + raise ValueError('Cannot bind to a random port with enabled ' + 'reloader if the Python interpreter does ' + 'not support socket opening by fd.') + + # Create and destroy a socket so that any exceptions are + # raised before we spawn a separate Python interpreter and + # lose this ability. + address_family = select_ip_version(hostname, port) + s = socket.socket(address_family, socket.SOCK_STREAM) + s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) + s.bind(get_sockaddr(hostname, port, address_family)) + if hasattr(s, 'set_inheritable'): + s.set_inheritable(True) + + # If we can open the socket by file descriptor, then we can just + # reuse this one and our socket will survive the restarts. + if can_open_by_fd: + os.environ['WERKZEUG_SERVER_FD'] = str(s.fileno()) + s.listen(LISTEN_QUEUE) + log_startup(s) + else: + s.close() + + # Do not use relative imports, otherwise "python -m werkzeug.serving" + # breaks. + from werkzeug._reloader import run_with_reloader + run_with_reloader(inner, extra_files, reloader_interval, + reloader_type) + else: + inner() + + +def run_with_reloader(*args, **kwargs): + # People keep using undocumented APIs. Do not use this function + # please, we do not guarantee that it continues working. + from werkzeug._reloader import run_with_reloader + return run_with_reloader(*args, **kwargs) + + +def main(): + '''A simple command-line interface for :py:func:`run_simple`.''' + + # in contrast to argparse, this works at least under Python < 2.7 + import optparse + from werkzeug.utils import import_string + + parser = optparse.OptionParser( + usage='Usage: %prog [options] app_module:app_object') + parser.add_option('-b', '--bind', dest='address', + help='The hostname:port the app should listen on.') + parser.add_option('-d', '--debug', dest='use_debugger', + action='store_true', default=False, + help='Use Werkzeug\'s debugger.') + parser.add_option('-r', '--reload', dest='use_reloader', + action='store_true', default=False, + help='Reload Python process if modules change.') + options, args = parser.parse_args() + + hostname, port = None, None + if options.address: + address = options.address.split(':') + hostname = address[0] + if len(address) > 1: + port = address[1] + + if len(args) != 1: + sys.stdout.write('No application supplied, or too much. See --help\n') + sys.exit(1) + app = import_string(args[0]) + + run_simple( + hostname=(hostname or '127.0.0.1'), port=int(port or 5000), + application=app, use_reloader=options.use_reloader, + use_debugger=options.use_debugger + ) + +if __name__ == '__main__': + main() diff --git a/pyextra/werkzeug/test.py b/pyextra/werkzeug/test.py new file mode 100644 index 00000000000000..acd21793df7133 --- /dev/null +++ b/pyextra/werkzeug/test.py @@ -0,0 +1,948 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.test + ~~~~~~~~~~~~~ + + This module implements a client to WSGI applications for testing. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import sys +import mimetypes +from time import time +from random import random +from itertools import chain +from tempfile import TemporaryFile +from io import BytesIO + +try: + from urllib2 import Request as U2Request +except ImportError: + from urllib.request import Request as U2Request +try: + from http.cookiejar import CookieJar +except ImportError: # Py2 + from cookielib import CookieJar + +from werkzeug._compat import iterlists, iteritems, itervalues, to_bytes, \ + string_types, text_type, reraise, wsgi_encoding_dance, \ + make_literal_wrapper +from werkzeug._internal import _empty_stream, _get_environ +from werkzeug.wrappers import BaseRequest +from werkzeug.urls import url_encode, url_fix, iri_to_uri, url_unquote, \ + url_unparse, url_parse +from werkzeug.wsgi import get_host, get_current_url, ClosingIterator +from werkzeug.utils import dump_cookie, get_content_type +from werkzeug.datastructures import FileMultiDict, MultiDict, \ + CombinedMultiDict, Headers, FileStorage, CallbackDict +from werkzeug.http import dump_options_header, parse_options_header + + +def stream_encode_multipart(values, use_tempfile=True, threshold=1024 * 500, + boundary=None, charset='utf-8'): + """Encode a dict of values (either strings or file descriptors or + :class:`FileStorage` objects.) into a multipart encoded string stored + in a file descriptor. + """ + if boundary is None: + boundary = '---------------WerkzeugFormPart_%s%s' % (time(), random()) + _closure = [BytesIO(), 0, False] + + if use_tempfile: + def write_binary(string): + stream, total_length, on_disk = _closure + if on_disk: + stream.write(string) + else: + length = len(string) + if length + _closure[1] <= threshold: + stream.write(string) + else: + new_stream = TemporaryFile('wb+') + new_stream.write(stream.getvalue()) + new_stream.write(string) + _closure[0] = new_stream + _closure[2] = True + _closure[1] = total_length + length + else: + write_binary = _closure[0].write + + def write(string): + write_binary(string.encode(charset)) + + if not isinstance(values, MultiDict): + values = MultiDict(values) + + for key, values in iterlists(values): + for value in values: + write('--%s\r\nContent-Disposition: form-data; name="%s"' % + (boundary, key)) + reader = getattr(value, 'read', None) + if reader is not None: + filename = getattr(value, 'filename', + getattr(value, 'name', None)) + content_type = getattr(value, 'content_type', None) + if content_type is None: + content_type = filename and \ + mimetypes.guess_type(filename)[0] or \ + 'application/octet-stream' + if filename is not None: + write('; filename="%s"\r\n' % filename) + else: + write('\r\n') + write('Content-Type: %s\r\n\r\n' % content_type) + while 1: + chunk = reader(16384) + if not chunk: + break + write_binary(chunk) + else: + if not isinstance(value, string_types): + value = str(value) + + value = to_bytes(value, charset) + write('\r\n\r\n') + write_binary(value) + write('\r\n') + write('--%s--\r\n' % boundary) + + length = int(_closure[0].tell()) + _closure[0].seek(0) + return _closure[0], length, boundary + + +def encode_multipart(values, boundary=None, charset='utf-8'): + """Like `stream_encode_multipart` but returns a tuple in the form + (``boundary``, ``data``) where data is a bytestring. + """ + stream, length, boundary = stream_encode_multipart( + values, use_tempfile=False, boundary=boundary, charset=charset) + return boundary, stream.read() + + +def File(fd, filename=None, mimetype=None): + """Backwards compat.""" + from warnings import warn + warn(DeprecationWarning('werkzeug.test.File is deprecated, use the ' + 'EnvironBuilder or FileStorage instead')) + return FileStorage(fd, filename=filename, content_type=mimetype) + + +class _TestCookieHeaders(object): + + """A headers adapter for cookielib + """ + + def __init__(self, headers): + self.headers = headers + + def getheaders(self, name): + headers = [] + name = name.lower() + for k, v in self.headers: + if k.lower() == name: + headers.append(v) + return headers + + def get_all(self, name, default=None): + rv = [] + for k, v in self.headers: + if k.lower() == name.lower(): + rv.append(v) + return rv or default or [] + + +class _TestCookieResponse(object): + + """Something that looks like a httplib.HTTPResponse, but is actually just an + adapter for our test responses to make them available for cookielib. + """ + + def __init__(self, headers): + self.headers = _TestCookieHeaders(headers) + + def info(self): + return self.headers + + +class _TestCookieJar(CookieJar): + + """A cookielib.CookieJar modified to inject and read cookie headers from + and to wsgi environments, and wsgi application responses. + """ + + def inject_wsgi(self, environ): + """Inject the cookies as client headers into the server's wsgi + environment. + """ + cvals = [] + for cookie in self: + cvals.append('%s=%s' % (cookie.name, cookie.value)) + if cvals: + environ['HTTP_COOKIE'] = '; '.join(cvals) + + def extract_wsgi(self, environ, headers): + """Extract the server's set-cookie headers as cookies into the + cookie jar. + """ + self.extract_cookies( + _TestCookieResponse(headers), + U2Request(get_current_url(environ)), + ) + + +def _iter_data(data): + """Iterates over a `dict` or :class:`MultiDict` yielding all keys and + values. + This is used to iterate over the data passed to the + :class:`EnvironBuilder`. + """ + if isinstance(data, MultiDict): + for key, values in iterlists(data): + for value in values: + yield key, value + else: + for key, values in iteritems(data): + if isinstance(values, list): + for value in values: + yield key, value + else: + yield key, values + + +class EnvironBuilder(object): + + """This class can be used to conveniently create a WSGI environment + for testing purposes. It can be used to quickly create WSGI environments + or request objects from arbitrary data. + + The signature of this class is also used in some other places as of + Werkzeug 0.5 (:func:`create_environ`, :meth:`BaseResponse.from_values`, + :meth:`Client.open`). Because of this most of the functionality is + available through the constructor alone. + + Files and regular form data can be manipulated independently of each + other with the :attr:`form` and :attr:`files` attributes, but are + passed with the same argument to the constructor: `data`. + + `data` can be any of these values: + + - a `str` or `bytes` object: The object is converted into an + :attr:`input_stream`, the :attr:`content_length` is set and you have to + provide a :attr:`content_type`. + - a `dict` or :class:`MultiDict`: The keys have to be strings. The values + have to be either any of the following objects, or a list of any of the + following objects: + + - a :class:`file`-like object: These are converted into + :class:`FileStorage` objects automatically. + - a `tuple`: The :meth:`~FileMultiDict.add_file` method is called + with the key and the unpacked `tuple` items as positional + arguments. + - a `str`: The string is set as form data for the associated key. + - a file-like object: The object content is loaded in memory and then + handled like a regular `str` or a `bytes`. + + .. versionadded:: 0.6 + `path` and `base_url` can now be unicode strings that are encoded using + the :func:`iri_to_uri` function. + + :param path: the path of the request. In the WSGI environment this will + end up as `PATH_INFO`. If the `query_string` is not defined + and there is a question mark in the `path` everything after + it is used as query string. + :param base_url: the base URL is a URL that is used to extract the WSGI + URL scheme, host (server name + server port) and the + script root (`SCRIPT_NAME`). + :param query_string: an optional string or dict with URL parameters. + :param method: the HTTP method to use, defaults to `GET`. + :param input_stream: an optional input stream. Do not specify this and + `data`. As soon as an input stream is set you can't + modify :attr:`args` and :attr:`files` unless you + set the :attr:`input_stream` to `None` again. + :param content_type: The content type for the request. As of 0.5 you + don't have to provide this when specifying files + and form data via `data`. + :param content_length: The content length for the request. You don't + have to specify this when providing data via + `data`. + :param errors_stream: an optional error stream that is used for + `wsgi.errors`. Defaults to :data:`stderr`. + :param multithread: controls `wsgi.multithread`. Defaults to `False`. + :param multiprocess: controls `wsgi.multiprocess`. Defaults to `False`. + :param run_once: controls `wsgi.run_once`. Defaults to `False`. + :param headers: an optional list or :class:`Headers` object of headers. + :param data: a string or dict of form data or a file-object. + See explanation above. + :param environ_base: an optional dict of environment defaults. + :param environ_overrides: an optional dict of environment overrides. + :param charset: the charset used to encode unicode data. + """ + + #: the server protocol to use. defaults to HTTP/1.1 + server_protocol = 'HTTP/1.1' + + #: the wsgi version to use. defaults to (1, 0) + wsgi_version = (1, 0) + + #: the default request class for :meth:`get_request` + request_class = BaseRequest + + def __init__(self, path='/', base_url=None, query_string=None, + method='GET', input_stream=None, content_type=None, + content_length=None, errors_stream=None, multithread=False, + multiprocess=False, run_once=False, headers=None, data=None, + environ_base=None, environ_overrides=None, charset='utf-8', + mimetype=None): + path_s = make_literal_wrapper(path) + if query_string is None and path_s('?') in path: + path, query_string = path.split(path_s('?'), 1) + self.charset = charset + self.path = iri_to_uri(path) + if base_url is not None: + base_url = url_fix(iri_to_uri(base_url, charset), charset) + self.base_url = base_url + if isinstance(query_string, (bytes, text_type)): + self.query_string = query_string + else: + if query_string is None: + query_string = MultiDict() + elif not isinstance(query_string, MultiDict): + query_string = MultiDict(query_string) + self.args = query_string + self.method = method + if headers is None: + headers = Headers() + elif not isinstance(headers, Headers): + headers = Headers(headers) + self.headers = headers + if content_type is not None: + self.content_type = content_type + if errors_stream is None: + errors_stream = sys.stderr + self.errors_stream = errors_stream + self.multithread = multithread + self.multiprocess = multiprocess + self.run_once = run_once + self.environ_base = environ_base + self.environ_overrides = environ_overrides + self.input_stream = input_stream + self.content_length = content_length + self.closed = False + + if data: + if input_stream is not None: + raise TypeError('can\'t provide input stream and data') + if hasattr(data, 'read'): + data = data.read() + if isinstance(data, text_type): + data = data.encode(self.charset) + if isinstance(data, bytes): + self.input_stream = BytesIO(data) + if self.content_length is None: + self.content_length = len(data) + else: + for key, value in _iter_data(data): + if isinstance(value, (tuple, dict)) or \ + hasattr(value, 'read'): + self._add_file_from_data(key, value) + else: + self.form.setlistdefault(key).append(value) + + if mimetype is not None: + self.mimetype = mimetype + + def _add_file_from_data(self, key, value): + """Called in the EnvironBuilder to add files from the data dict.""" + if isinstance(value, tuple): + self.files.add_file(key, *value) + elif isinstance(value, dict): + from warnings import warn + warn(DeprecationWarning('it\'s no longer possible to pass dicts ' + 'as `data`. Use tuples or FileStorage ' + 'objects instead'), stacklevel=2) + value = dict(value) + mimetype = value.pop('mimetype', None) + if mimetype is not None: + value['content_type'] = mimetype + self.files.add_file(key, **value) + else: + self.files.add_file(key, value) + + def _get_base_url(self): + return url_unparse((self.url_scheme, self.host, + self.script_root, '', '')).rstrip('/') + '/' + + def _set_base_url(self, value): + if value is None: + scheme = 'http' + netloc = 'localhost' + script_root = '' + else: + scheme, netloc, script_root, qs, anchor = url_parse(value) + if qs or anchor: + raise ValueError('base url must not contain a query string ' + 'or fragment') + self.script_root = script_root.rstrip('/') + self.host = netloc + self.url_scheme = scheme + + base_url = property(_get_base_url, _set_base_url, doc=''' + The base URL is a URL that is used to extract the WSGI + URL scheme, host (server name + server port) and the + script root (`SCRIPT_NAME`).''') + del _get_base_url, _set_base_url + + def _get_content_type(self): + ct = self.headers.get('Content-Type') + if ct is None and not self._input_stream: + if self._files: + return 'multipart/form-data' + elif self._form: + return 'application/x-www-form-urlencoded' + return None + return ct + + def _set_content_type(self, value): + if value is None: + self.headers.pop('Content-Type', None) + else: + self.headers['Content-Type'] = value + + content_type = property(_get_content_type, _set_content_type, doc=''' + The content type for the request. Reflected from and to the + :attr:`headers`. Do not set if you set :attr:`files` or + :attr:`form` for auto detection.''') + del _get_content_type, _set_content_type + + def _get_content_length(self): + return self.headers.get('Content-Length', type=int) + + def _get_mimetype(self): + ct = self.content_type + if ct: + return ct.split(';')[0].strip() + + def _set_mimetype(self, value): + self.content_type = get_content_type(value, self.charset) + + def _get_mimetype_params(self): + def on_update(d): + self.headers['Content-Type'] = \ + dump_options_header(self.mimetype, d) + d = parse_options_header(self.headers.get('content-type', ''))[1] + return CallbackDict(d, on_update) + + mimetype = property(_get_mimetype, _set_mimetype, doc=''' + The mimetype (content type without charset etc.) + + .. versionadded:: 0.14 + ''') + mimetype_params = property(_get_mimetype_params, doc=''' + The mimetype parameters as dict. For example if the content + type is ``text/html; charset=utf-8`` the params would be + ``{'charset': 'utf-8'}``. + + .. versionadded:: 0.14 + ''') + del _get_mimetype, _set_mimetype, _get_mimetype_params + + def _set_content_length(self, value): + if value is None: + self.headers.pop('Content-Length', None) + else: + self.headers['Content-Length'] = str(value) + + content_length = property(_get_content_length, _set_content_length, doc=''' + The content length as integer. Reflected from and to the + :attr:`headers`. Do not set if you set :attr:`files` or + :attr:`form` for auto detection.''') + del _get_content_length, _set_content_length + + def form_property(name, storage, doc): + key = '_' + name + + def getter(self): + if self._input_stream is not None: + raise AttributeError('an input stream is defined') + rv = getattr(self, key) + if rv is None: + rv = storage() + setattr(self, key, rv) + + return rv + + def setter(self, value): + self._input_stream = None + setattr(self, key, value) + return property(getter, setter, doc=doc) + + form = form_property('form', MultiDict, doc=''' + A :class:`MultiDict` of form values.''') + files = form_property('files', FileMultiDict, doc=''' + A :class:`FileMultiDict` of uploaded files. You can use the + :meth:`~FileMultiDict.add_file` method to add new files to the + dict.''') + del form_property + + def _get_input_stream(self): + return self._input_stream + + def _set_input_stream(self, value): + self._input_stream = value + self._form = self._files = None + + input_stream = property(_get_input_stream, _set_input_stream, doc=''' + An optional input stream. If you set this it will clear + :attr:`form` and :attr:`files`.''') + del _get_input_stream, _set_input_stream + + def _get_query_string(self): + if self._query_string is None: + if self._args is not None: + return url_encode(self._args, charset=self.charset) + return '' + return self._query_string + + def _set_query_string(self, value): + self._query_string = value + self._args = None + + query_string = property(_get_query_string, _set_query_string, doc=''' + The query string. If you set this to a string :attr:`args` will + no longer be available.''') + del _get_query_string, _set_query_string + + def _get_args(self): + if self._query_string is not None: + raise AttributeError('a query string is defined') + if self._args is None: + self._args = MultiDict() + return self._args + + def _set_args(self, value): + self._query_string = None + self._args = value + + args = property(_get_args, _set_args, doc=''' + The URL arguments as :class:`MultiDict`.''') + del _get_args, _set_args + + @property + def server_name(self): + """The server name (read-only, use :attr:`host` to set)""" + return self.host.split(':', 1)[0] + + @property + def server_port(self): + """The server port as integer (read-only, use :attr:`host` to set)""" + pieces = self.host.split(':', 1) + if len(pieces) == 2 and pieces[1].isdigit(): + return int(pieces[1]) + elif self.url_scheme == 'https': + return 443 + return 80 + + def __del__(self): + try: + self.close() + except Exception: + pass + + def close(self): + """Closes all files. If you put real :class:`file` objects into the + :attr:`files` dict you can call this method to automatically close + them all in one go. + """ + if self.closed: + return + try: + files = itervalues(self.files) + except AttributeError: + files = () + for f in files: + try: + f.close() + except Exception: + pass + self.closed = True + + def get_environ(self): + """Return the built environ.""" + input_stream = self.input_stream + content_length = self.content_length + + mimetype = self.mimetype + content_type = self.content_type + + if input_stream is not None: + start_pos = input_stream.tell() + input_stream.seek(0, 2) + end_pos = input_stream.tell() + input_stream.seek(start_pos) + content_length = end_pos - start_pos + elif mimetype == 'multipart/form-data': + values = CombinedMultiDict([self.form, self.files]) + input_stream, content_length, boundary = \ + stream_encode_multipart(values, charset=self.charset) + content_type = mimetype + '; boundary="%s"' % boundary + elif mimetype == 'application/x-www-form-urlencoded': + # XXX: py2v3 review + values = url_encode(self.form, charset=self.charset) + values = values.encode('ascii') + content_length = len(values) + input_stream = BytesIO(values) + else: + input_stream = _empty_stream + + result = {} + if self.environ_base: + result.update(self.environ_base) + + def _path_encode(x): + return wsgi_encoding_dance(url_unquote(x, self.charset), self.charset) + + qs = wsgi_encoding_dance(self.query_string) + + result.update({ + 'REQUEST_METHOD': self.method, + 'SCRIPT_NAME': _path_encode(self.script_root), + 'PATH_INFO': _path_encode(self.path), + 'QUERY_STRING': qs, + 'SERVER_NAME': self.server_name, + 'SERVER_PORT': str(self.server_port), + 'HTTP_HOST': self.host, + 'SERVER_PROTOCOL': self.server_protocol, + 'CONTENT_TYPE': content_type or '', + 'CONTENT_LENGTH': str(content_length or '0'), + 'wsgi.version': self.wsgi_version, + 'wsgi.url_scheme': self.url_scheme, + 'wsgi.input': input_stream, + 'wsgi.errors': self.errors_stream, + 'wsgi.multithread': self.multithread, + 'wsgi.multiprocess': self.multiprocess, + 'wsgi.run_once': self.run_once + }) + for key, value in self.headers.to_wsgi_list(): + result['HTTP_%s' % key.upper().replace('-', '_')] = value + if self.environ_overrides: + result.update(self.environ_overrides) + return result + + def get_request(self, cls=None): + """Returns a request with the data. If the request class is not + specified :attr:`request_class` is used. + + :param cls: The request wrapper to use. + """ + if cls is None: + cls = self.request_class + return cls(self.get_environ()) + + +class ClientRedirectError(Exception): + + """ + If a redirect loop is detected when using follow_redirects=True with + the :cls:`Client`, then this exception is raised. + """ + + +class Client(object): + + """This class allows to send requests to a wrapped application. + + The response wrapper can be a class or factory function that takes + three arguments: app_iter, status and headers. The default response + wrapper just returns a tuple. + + Example:: + + class ClientResponse(BaseResponse): + ... + + client = Client(MyApplication(), response_wrapper=ClientResponse) + + The use_cookies parameter indicates whether cookies should be stored and + sent for subsequent requests. This is True by default, but passing False + will disable this behaviour. + + If you want to request some subdomain of your application you may set + `allow_subdomain_redirects` to `True` as if not no external redirects + are allowed. + + .. versionadded:: 0.5 + `use_cookies` is new in this version. Older versions did not provide + builtin cookie support. + + .. versionadded:: 0.14 + The `mimetype` parameter was added. + """ + + def __init__(self, application, response_wrapper=None, use_cookies=True, + allow_subdomain_redirects=False): + self.application = application + self.response_wrapper = response_wrapper + if use_cookies: + self.cookie_jar = _TestCookieJar() + else: + self.cookie_jar = None + self.allow_subdomain_redirects = allow_subdomain_redirects + + def set_cookie(self, server_name, key, value='', max_age=None, + expires=None, path='/', domain=None, secure=None, + httponly=False, charset='utf-8'): + """Sets a cookie in the client's cookie jar. The server name + is required and has to match the one that is also passed to + the open call. + """ + assert self.cookie_jar is not None, 'cookies disabled' + header = dump_cookie(key, value, max_age, expires, path, domain, + secure, httponly, charset) + environ = create_environ(path, base_url='http://' + server_name) + headers = [('Set-Cookie', header)] + self.cookie_jar.extract_wsgi(environ, headers) + + def delete_cookie(self, server_name, key, path='/', domain=None): + """Deletes a cookie in the test client.""" + self.set_cookie(server_name, key, expires=0, max_age=0, + path=path, domain=domain) + + def run_wsgi_app(self, environ, buffered=False): + """Runs the wrapped WSGI app with the given environment.""" + if self.cookie_jar is not None: + self.cookie_jar.inject_wsgi(environ) + rv = run_wsgi_app(self.application, environ, buffered=buffered) + if self.cookie_jar is not None: + self.cookie_jar.extract_wsgi(environ, rv[2]) + return rv + + def resolve_redirect(self, response, new_location, environ, buffered=False): + """Resolves a single redirect and triggers the request again + directly on this redirect client. + """ + scheme, netloc, script_root, qs, anchor = url_parse(new_location) + base_url = url_unparse((scheme, netloc, '', '', '')).rstrip('/') + '/' + + cur_server_name = netloc.split(':', 1)[0].split('.') + real_server_name = get_host(environ).rsplit(':', 1)[0].split('.') + if cur_server_name == ['']: + # this is a local redirect having autocorrect_location_header=False + cur_server_name = real_server_name + base_url = EnvironBuilder(environ).base_url + + if self.allow_subdomain_redirects: + allowed = cur_server_name[-len(real_server_name):] == real_server_name + else: + allowed = cur_server_name == real_server_name + + if not allowed: + raise RuntimeError('%r does not support redirect to ' + 'external targets' % self.__class__) + + status_code = int(response[1].split(None, 1)[0]) + if status_code == 307: + method = environ['REQUEST_METHOD'] + else: + method = 'GET' + + # For redirect handling we temporarily disable the response + # wrapper. This is not threadsafe but not a real concern + # since the test client must not be shared anyways. + old_response_wrapper = self.response_wrapper + self.response_wrapper = None + try: + return self.open(path=script_root, base_url=base_url, + query_string=qs, as_tuple=True, + buffered=buffered, method=method) + finally: + self.response_wrapper = old_response_wrapper + + def open(self, *args, **kwargs): + """Takes the same arguments as the :class:`EnvironBuilder` class with + some additions: You can provide a :class:`EnvironBuilder` or a WSGI + environment as only argument instead of the :class:`EnvironBuilder` + arguments and two optional keyword arguments (`as_tuple`, `buffered`) + that change the type of the return value or the way the application is + executed. + + .. versionchanged:: 0.5 + If a dict is provided as file in the dict for the `data` parameter + the content type has to be called `content_type` now instead of + `mimetype`. This change was made for consistency with + :class:`werkzeug.FileWrapper`. + + The `follow_redirects` parameter was added to :func:`open`. + + Additional parameters: + + :param as_tuple: Returns a tuple in the form ``(environ, result)`` + :param buffered: Set this to True to buffer the application run. + This will automatically close the application for + you as well. + :param follow_redirects: Set this to True if the `Client` should + follow HTTP redirects. + """ + as_tuple = kwargs.pop('as_tuple', False) + buffered = kwargs.pop('buffered', False) + follow_redirects = kwargs.pop('follow_redirects', False) + environ = None + if not kwargs and len(args) == 1: + if isinstance(args[0], EnvironBuilder): + environ = args[0].get_environ() + elif isinstance(args[0], dict): + environ = args[0] + if environ is None: + builder = EnvironBuilder(*args, **kwargs) + try: + environ = builder.get_environ() + finally: + builder.close() + + response = self.run_wsgi_app(environ, buffered=buffered) + + # handle redirects + redirect_chain = [] + while 1: + status_code = int(response[1].split(None, 1)[0]) + if status_code not in (301, 302, 303, 305, 307) \ + or not follow_redirects: + break + new_location = response[2]['location'] + new_redirect_entry = (new_location, status_code) + if new_redirect_entry in redirect_chain: + raise ClientRedirectError('loop detected') + redirect_chain.append(new_redirect_entry) + environ, response = self.resolve_redirect(response, new_location, + environ, + buffered=buffered) + + if self.response_wrapper is not None: + response = self.response_wrapper(*response) + if as_tuple: + return environ, response + return response + + def get(self, *args, **kw): + """Like open but method is enforced to GET.""" + kw['method'] = 'GET' + return self.open(*args, **kw) + + def patch(self, *args, **kw): + """Like open but method is enforced to PATCH.""" + kw['method'] = 'PATCH' + return self.open(*args, **kw) + + def post(self, *args, **kw): + """Like open but method is enforced to POST.""" + kw['method'] = 'POST' + return self.open(*args, **kw) + + def head(self, *args, **kw): + """Like open but method is enforced to HEAD.""" + kw['method'] = 'HEAD' + return self.open(*args, **kw) + + def put(self, *args, **kw): + """Like open but method is enforced to PUT.""" + kw['method'] = 'PUT' + return self.open(*args, **kw) + + def delete(self, *args, **kw): + """Like open but method is enforced to DELETE.""" + kw['method'] = 'DELETE' + return self.open(*args, **kw) + + def options(self, *args, **kw): + """Like open but method is enforced to OPTIONS.""" + kw['method'] = 'OPTIONS' + return self.open(*args, **kw) + + def trace(self, *args, **kw): + """Like open but method is enforced to TRACE.""" + kw['method'] = 'TRACE' + return self.open(*args, **kw) + + def __repr__(self): + return '<%s %r>' % ( + self.__class__.__name__, + self.application + ) + + +def create_environ(*args, **kwargs): + """Create a new WSGI environ dict based on the values passed. The first + parameter should be the path of the request which defaults to '/'. The + second one can either be an absolute path (in that case the host is + localhost:80) or a full path to the request with scheme, netloc port and + the path to the script. + + This accepts the same arguments as the :class:`EnvironBuilder` + constructor. + + .. versionchanged:: 0.5 + This function is now a thin wrapper over :class:`EnvironBuilder` which + was added in 0.5. The `headers`, `environ_base`, `environ_overrides` + and `charset` parameters were added. + """ + builder = EnvironBuilder(*args, **kwargs) + try: + return builder.get_environ() + finally: + builder.close() + + +def run_wsgi_app(app, environ, buffered=False): + """Return a tuple in the form (app_iter, status, headers) of the + application output. This works best if you pass it an application that + returns an iterator all the time. + + Sometimes applications may use the `write()` callable returned + by the `start_response` function. This tries to resolve such edge + cases automatically. But if you don't get the expected output you + should set `buffered` to `True` which enforces buffering. + + If passed an invalid WSGI application the behavior of this function is + undefined. Never pass non-conforming WSGI applications to this function. + + :param app: the application to execute. + :param buffered: set to `True` to enforce buffering. + :return: tuple in the form ``(app_iter, status, headers)`` + """ + environ = _get_environ(environ) + response = [] + buffer = [] + + def start_response(status, headers, exc_info=None): + if exc_info is not None: + reraise(*exc_info) + response[:] = [status, headers] + return buffer.append + + app_rv = app(environ, start_response) + close_func = getattr(app_rv, 'close', None) + app_iter = iter(app_rv) + + # when buffering we emit the close call early and convert the + # application iterator into a regular list + if buffered: + try: + app_iter = list(app_iter) + finally: + if close_func is not None: + close_func() + + # otherwise we iterate the application iter until we have a response, chain + # the already received data with the already collected data and wrap it in + # a new `ClosingIterator` if we need to restore a `close` callable from the + # original return value. + else: + while not response: + buffer.append(next(app_iter)) + if buffer: + app_iter = chain(buffer, app_iter) + if close_func is not None and app_iter is not app_rv: + app_iter = ClosingIterator(app_iter, close_func) + + return app_iter, response[0], Headers(response[1]) diff --git a/pyextra/werkzeug/testapp.py b/pyextra/werkzeug/testapp.py new file mode 100644 index 00000000000000..595555a09b00af --- /dev/null +++ b/pyextra/werkzeug/testapp.py @@ -0,0 +1,230 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.testapp + ~~~~~~~~~~~~~~~~ + + Provide a small test application that can be used to test a WSGI server + and check it for WSGI compliance. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import os +import sys +import werkzeug +from textwrap import wrap +from werkzeug.wrappers import BaseRequest as Request, BaseResponse as Response +from werkzeug.utils import escape +import base64 + +logo = Response(base64.b64decode(''' +R0lGODlhoACgAOMIAAEDACwpAEpCAGdgAJaKAM28AOnVAP3rAP///////// +//////////////////////yH5BAEKAAgALAAAAACgAKAAAAT+EMlJq704680R+F0ojmRpnuj0rWnrv +nB8rbRs33gu0bzu/0AObxgsGn3D5HHJbCUFyqZ0ukkSDlAidctNFg7gbI9LZlrBaHGtzAae0eloe25 +7w9EDOX2fst/xenyCIn5/gFqDiVVDV4aGeYiKkhSFjnCQY5OTlZaXgZp8nJ2ekaB0SQOjqphrpnOiq +ncEn65UsLGytLVmQ6m4sQazpbtLqL/HwpnER8bHyLrLOc3Oz8PRONPU1crXN9na263dMt/g4SzjMeX +m5yDpLqgG7OzJ4u8lT/P69ej3JPn69kHzN2OIAHkB9RUYSFCFQYQJFTIkCDBiwoXWGnowaLEjRm7+G +p9A7Hhx4rUkAUaSLJlxHMqVMD/aSycSZkyTplCqtGnRAM5NQ1Ly5OmzZc6gO4d6DGAUKA+hSocWYAo +SlM6oUWX2O/o0KdaVU5vuSQLAa0ADwQgMEMB2AIECZhVSnTno6spgbtXmHcBUrQACcc2FrTrWS8wAf +78cMFBgwIBgbN+qvTt3ayikRBk7BoyGAGABAdYyfdzRQGV3l4coxrqQ84GpUBmrdR3xNIDUPAKDBSA +ADIGDhhqTZIWaDcrVX8EsbNzbkvCOxG8bN5w8ly9H8jyTJHC6DFndQydbguh2e/ctZJFXRxMAqqPVA +tQH5E64SPr1f0zz7sQYjAHg0In+JQ11+N2B0XXBeeYZgBZFx4tqBToiTCPv0YBgQv8JqA6BEf6RhXx +w1ENhRBnWV8ctEX4Ul2zc3aVGcQNC2KElyTDYyYUWvShdjDyMOGMuFjqnII45aogPhz/CodUHFwaDx +lTgsaOjNyhGWJQd+lFoAGk8ObghI0kawg+EV5blH3dr+digkYuAGSaQZFHFz2P/cTaLmhF52QeSb45 +Jwxd+uSVGHlqOZpOeJpCFZ5J+rkAkFjQ0N1tah7JJSZUFNsrkeJUJMIBi8jyaEKIhKPomnC91Uo+NB +yyaJ5umnnpInIFh4t6ZSpGaAVmizqjpByDegYl8tPE0phCYrhcMWSv+uAqHfgH88ak5UXZmlKLVJhd +dj78s1Fxnzo6yUCrV6rrDOkluG+QzCAUTbCwf9SrmMLzK6p+OPHx7DF+bsfMRq7Ec61Av9i6GLw23r +idnZ+/OO0a99pbIrJkproCQMA17OPG6suq3cca5ruDfXCCDoS7BEdvmJn5otdqscn+uogRHHXs8cbh +EIfYaDY1AkrC0cqwcZpnM6ludx72x0p7Fo/hZAcpJDjax0UdHavMKAbiKltMWCF3xxh9k25N/Viud8 +ba78iCvUkt+V6BpwMlErmcgc502x+u1nSxJSJP9Mi52awD1V4yB/QHONsnU3L+A/zR4VL/indx/y64 +gqcj+qgTeweM86f0Qy1QVbvmWH1D9h+alqg254QD8HJXHvjQaGOqEqC22M54PcftZVKVSQG9jhkv7C +JyTyDoAJfPdu8v7DRZAxsP/ky9MJ3OL36DJfCFPASC3/aXlfLOOON9vGZZHydGf8LnxYJuuVIbl83y +Az5n/RPz07E+9+zw2A2ahz4HxHo9Kt79HTMx1Q7ma7zAzHgHqYH0SoZWyTuOLMiHwSfZDAQTn0ajk9 +YQqodnUYjByQZhZak9Wu4gYQsMyEpIOAOQKze8CmEF45KuAHTvIDOfHJNipwoHMuGHBnJElUoDmAyX +c2Qm/R8Ah/iILCCJOEokGowdhDYc/yoL+vpRGwyVSCWFYZNljkhEirGXsalWcAgOdeAdoXcktF2udb +qbUhjWyMQxYO01o6KYKOr6iK3fE4MaS+DsvBsGOBaMb0Y6IxADaJhFICaOLmiWTlDAnY1KzDG4ambL +cWBA8mUzjJsN2KjSaSXGqMCVXYpYkj33mcIApyhQf6YqgeNAmNvuC0t4CsDbSshZJkCS1eNisKqlyG +cF8G2JeiDX6tO6Mv0SmjCa3MFb0bJaGPMU0X7c8XcpvMaOQmCajwSeY9G0WqbBmKv34DsMIEztU6Y2 +KiDlFdt6jnCSqx7Dmt6XnqSKaFFHNO5+FmODxMCWBEaco77lNDGXBM0ECYB/+s7nKFdwSF5hgXumQe +EZ7amRg39RHy3zIjyRCykQh8Zo2iviRKyTDn/zx6EefptJj2Cw+Ep2FSc01U5ry4KLPYsTyWnVGnvb +UpyGlhjBUljyjHhWpf8OFaXwhp9O4T1gU9UeyPPa8A2l0p1kNqPXEVRm1AOs1oAGZU596t6SOR2mcB +Oco1srWtkaVrMUzIErrKri85keKqRQYX9VX0/eAUK1hrSu6HMEX3Qh2sCh0q0D2CtnUqS4hj62sE/z +aDs2Sg7MBS6xnQeooc2R2tC9YrKpEi9pLXfYXp20tDCpSP8rKlrD4axprb9u1Df5hSbz9QU0cRpfgn +kiIzwKucd0wsEHlLpe5yHXuc6FrNelOl7pY2+11kTWx7VpRu97dXA3DO1vbkhcb4zyvERYajQgAADs +='''), mimetype='image/png') + + +TEMPLATE = u'''\ + +WSGI Information + +
+ +

WSGI Information

+

+ This page displays all available information about the WSGI server and + the underlying Python interpreter. +

Python Interpreter

+ + + + + + +
Python Version + %(python_version)s +
Platform + %(platform)s [%(os)s] +
API Version + %(api_version)s +
Byteorder + %(byteorder)s +
Werkzeug Version + %(werkzeug_version)s +
+

WSGI Environment

+ %(wsgi_env)s
+

Installed Eggs

+

+ The following python packages were installed on the system as + Python eggs: +

    %(python_eggs)s
+

System Path

+

+ The following paths are the current contents of the load path. The + following entries are looked up for Python packages. Note that not + all items in this path are folders. Gray and underlined items are + entries pointing to invalid resources or used by custom import hooks + such as the zip importer. +

+ Items with a bright background were expanded for display from a relative + path. If you encounter such paths in the output you might want to check + your setup as relative paths are usually problematic in multithreaded + environments. +

    %(sys_path)s
+
+''' + + +def iter_sys_path(): + if os.name == 'posix': + def strip(x): + prefix = os.path.expanduser('~') + if x.startswith(prefix): + x = '~' + x[len(prefix):] + return x + else: + strip = lambda x: x + + cwd = os.path.abspath(os.getcwd()) + for item in sys.path: + path = os.path.join(cwd, item or os.path.curdir) + yield strip(os.path.normpath(path)), \ + not os.path.isdir(path), path != item + + +def render_testapp(req): + try: + import pkg_resources + except ImportError: + eggs = () + else: + eggs = sorted(pkg_resources.working_set, + key=lambda x: x.project_name.lower()) + python_eggs = [] + for egg in eggs: + try: + version = egg.version + except (ValueError, AttributeError): + version = 'unknown' + python_eggs.append('
  • %s [%s]' % ( + escape(egg.project_name), + escape(version) + )) + + wsgi_env = [] + sorted_environ = sorted(req.environ.items(), + key=lambda x: repr(x[0]).lower()) + for key, value in sorted_environ: + wsgi_env.append('%s%s' % ( + escape(str(key)), + ' '.join(wrap(escape(repr(value)))) + )) + + sys_path = [] + for item, virtual, expanded in iter_sys_path(): + class_ = [] + if virtual: + class_.append('virtual') + if expanded: + class_.append('exp') + sys_path.append('%s' % ( + class_ and ' class="%s"' % ' '.join(class_) or '', + escape(item) + )) + + return (TEMPLATE % { + 'python_version': '
    '.join(escape(sys.version).splitlines()), + 'platform': escape(sys.platform), + 'os': escape(os.name), + 'api_version': sys.api_version, + 'byteorder': sys.byteorder, + 'werkzeug_version': werkzeug.__version__, + 'python_eggs': '\n'.join(python_eggs), + 'wsgi_env': '\n'.join(wsgi_env), + 'sys_path': '\n'.join(sys_path) + }).encode('utf-8') + + +def test_app(environ, start_response): + """Simple test application that dumps the environment. You can use + it to check if Werkzeug is working properly: + + .. sourcecode:: pycon + + >>> from werkzeug.serving import run_simple + >>> from werkzeug.testapp import test_app + >>> run_simple('localhost', 3000, test_app) + * Running on http://localhost:3000/ + + The application displays important information from the WSGI environment, + the Python interpreter and the installed libraries. + """ + req = Request(environ, populate_request=False) + if req.args.get('resource') == 'logo': + response = logo + else: + response = Response(render_testapp(req), mimetype='text/html') + return response(environ, start_response) + + +if __name__ == '__main__': + from werkzeug.serving import run_simple + run_simple('localhost', 5000, test_app, use_reloader=True) diff --git a/pyextra/werkzeug/urls.py b/pyextra/werkzeug/urls.py new file mode 100644 index 00000000000000..5bd9a40d899248 --- /dev/null +++ b/pyextra/werkzeug/urls.py @@ -0,0 +1,1007 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.urls + ~~~~~~~~~~~~~ + + ``werkzeug.urls`` used to provide several wrapper functions for Python 2 + urlparse, whose main purpose were to work around the behavior of the Py2 + stdlib and its lack of unicode support. While this was already a somewhat + inconvenient situation, it got even more complicated because Python 3's + ``urllib.parse`` actually does handle unicode properly. In other words, + this module would wrap two libraries with completely different behavior. So + now this module contains a 2-and-3-compatible backport of Python 3's + ``urllib.parse``, which is mostly API-compatible. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import os +import re +from werkzeug._compat import text_type, PY2, to_unicode, \ + to_native, implements_to_string, try_coerce_native, \ + normalize_string_tuple, make_literal_wrapper, \ + fix_tuple_repr +from werkzeug._internal import _encode_idna, _decode_idna +from werkzeug.datastructures import MultiDict, iter_multi_items +from collections import namedtuple + + +# A regular expression for what a valid schema looks like +_scheme_re = re.compile(r'^[a-zA-Z0-9+-.]+$') + +# Characters that are safe in any part of an URL. +_always_safe = (b'abcdefghijklmnopqrstuvwxyz' + b'ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789_.-+') + +_hexdigits = '0123456789ABCDEFabcdef' +_hextobyte = dict( + ((a + b).encode(), int(a + b, 16)) + for a in _hexdigits for b in _hexdigits +) +_bytetohex = [ + ('%%%02X' % char).encode('ascii') for char in range(256) +] + + +_URLTuple = fix_tuple_repr(namedtuple( + '_URLTuple', + ['scheme', 'netloc', 'path', 'query', 'fragment'] +)) + + +class BaseURL(_URLTuple): + + '''Superclass of :py:class:`URL` and :py:class:`BytesURL`.''' + __slots__ = () + + def replace(self, **kwargs): + """Return an URL with the same values, except for those parameters + given new values by whichever keyword arguments are specified.""" + return self._replace(**kwargs) + + @property + def host(self): + """The host part of the URL if available, otherwise `None`. The + host is either the hostname or the IP address mentioned in the + URL. It will not contain the port. + """ + return self._split_host()[0] + + @property + def ascii_host(self): + """Works exactly like :attr:`host` but will return a result that + is restricted to ASCII. If it finds a netloc that is not ASCII + it will attempt to idna decode it. This is useful for socket + operations when the URL might include internationalized characters. + """ + rv = self.host + if rv is not None and isinstance(rv, text_type): + try: + rv = _encode_idna(rv) + except UnicodeError: + rv = rv.encode('ascii', 'ignore') + return to_native(rv, 'ascii', 'ignore') + + @property + def port(self): + """The port in the URL as an integer if it was present, `None` + otherwise. This does not fill in default ports. + """ + try: + rv = int(to_native(self._split_host()[1])) + if 0 <= rv <= 65535: + return rv + except (ValueError, TypeError): + pass + + @property + def auth(self): + """The authentication part in the URL if available, `None` + otherwise. + """ + return self._split_netloc()[0] + + @property + def username(self): + """The username if it was part of the URL, `None` otherwise. + This undergoes URL decoding and will always be a unicode string. + """ + rv = self._split_auth()[0] + if rv is not None: + return _url_unquote_legacy(rv) + + @property + def raw_username(self): + """The username if it was part of the URL, `None` otherwise. + Unlike :attr:`username` this one is not being decoded. + """ + return self._split_auth()[0] + + @property + def password(self): + """The password if it was part of the URL, `None` otherwise. + This undergoes URL decoding and will always be a unicode string. + """ + rv = self._split_auth()[1] + if rv is not None: + return _url_unquote_legacy(rv) + + @property + def raw_password(self): + """The password if it was part of the URL, `None` otherwise. + Unlike :attr:`password` this one is not being decoded. + """ + return self._split_auth()[1] + + def decode_query(self, *args, **kwargs): + """Decodes the query part of the URL. Ths is a shortcut for + calling :func:`url_decode` on the query argument. The arguments and + keyword arguments are forwarded to :func:`url_decode` unchanged. + """ + return url_decode(self.query, *args, **kwargs) + + def join(self, *args, **kwargs): + """Joins this URL with another one. This is just a convenience + function for calling into :meth:`url_join` and then parsing the + return value again. + """ + return url_parse(url_join(self, *args, **kwargs)) + + def to_url(self): + """Returns a URL string or bytes depending on the type of the + information stored. This is just a convenience function + for calling :meth:`url_unparse` for this URL. + """ + return url_unparse(self) + + def decode_netloc(self): + """Decodes the netloc part into a string.""" + rv = _decode_idna(self.host or '') + + if ':' in rv: + rv = '[%s]' % rv + port = self.port + if port is not None: + rv = '%s:%d' % (rv, port) + auth = ':'.join(filter(None, [ + _url_unquote_legacy(self.raw_username or '', '/:%@'), + _url_unquote_legacy(self.raw_password or '', '/:%@'), + ])) + if auth: + rv = '%s@%s' % (auth, rv) + return rv + + def to_uri_tuple(self): + """Returns a :class:`BytesURL` tuple that holds a URI. This will + encode all the information in the URL properly to ASCII using the + rules a web browser would follow. + + It's usually more interesting to directly call :meth:`iri_to_uri` which + will return a string. + """ + return url_parse(iri_to_uri(self).encode('ascii')) + + def to_iri_tuple(self): + """Returns a :class:`URL` tuple that holds a IRI. This will try + to decode as much information as possible in the URL without + losing information similar to how a web browser does it for the + URL bar. + + It's usually more interesting to directly call :meth:`uri_to_iri` which + will return a string. + """ + return url_parse(uri_to_iri(self)) + + def get_file_location(self, pathformat=None): + """Returns a tuple with the location of the file in the form + ``(server, location)``. If the netloc is empty in the URL or + points to localhost, it's represented as ``None``. + + The `pathformat` by default is autodetection but needs to be set + when working with URLs of a specific system. The supported values + are ``'windows'`` when working with Windows or DOS paths and + ``'posix'`` when working with posix paths. + + If the URL does not point to to a local file, the server and location + are both represented as ``None``. + + :param pathformat: The expected format of the path component. + Currently ``'windows'`` and ``'posix'`` are + supported. Defaults to ``None`` which is + autodetect. + """ + if self.scheme != 'file': + return None, None + + path = url_unquote(self.path) + host = self.netloc or None + + if pathformat is None: + if os.name == 'nt': + pathformat = 'windows' + else: + pathformat = 'posix' + + if pathformat == 'windows': + if path[:1] == '/' and path[1:2].isalpha() and path[2:3] in '|:': + path = path[1:2] + ':' + path[3:] + windows_share = path[:3] in ('\\' * 3, '/' * 3) + import ntpath + path = ntpath.normpath(path) + # Windows shared drives are represented as ``\\host\\directory``. + # That results in a URL like ``file://///host/directory``, and a + # path like ``///host/directory``. We need to special-case this + # because the path contains the hostname. + if windows_share and host is None: + parts = path.lstrip('\\').split('\\', 1) + if len(parts) == 2: + host, path = parts + else: + host = parts[0] + path = '' + elif pathformat == 'posix': + import posixpath + path = posixpath.normpath(path) + else: + raise TypeError('Invalid path format %s' % repr(pathformat)) + + if host in ('127.0.0.1', '::1', 'localhost'): + host = None + + return host, path + + def _split_netloc(self): + if self._at in self.netloc: + return self.netloc.split(self._at, 1) + return None, self.netloc + + def _split_auth(self): + auth = self._split_netloc()[0] + if not auth: + return None, None + if self._colon not in auth: + return auth, None + return auth.split(self._colon, 1) + + def _split_host(self): + rv = self._split_netloc()[1] + if not rv: + return None, None + + if not rv.startswith(self._lbracket): + if self._colon in rv: + return rv.split(self._colon, 1) + return rv, None + + idx = rv.find(self._rbracket) + if idx < 0: + return rv, None + + host = rv[1:idx] + rest = rv[idx + 1:] + if rest.startswith(self._colon): + return host, rest[1:] + return host, None + + +@implements_to_string +class URL(BaseURL): + + """Represents a parsed URL. This behaves like a regular tuple but + also has some extra attributes that give further insight into the + URL. + """ + __slots__ = () + _at = '@' + _colon = ':' + _lbracket = '[' + _rbracket = ']' + + def __str__(self): + return self.to_url() + + def encode_netloc(self): + """Encodes the netloc part to an ASCII safe URL as bytes.""" + rv = self.ascii_host or '' + if ':' in rv: + rv = '[%s]' % rv + port = self.port + if port is not None: + rv = '%s:%d' % (rv, port) + auth = ':'.join(filter(None, [ + url_quote(self.raw_username or '', 'utf-8', 'strict', '/:%'), + url_quote(self.raw_password or '', 'utf-8', 'strict', '/:%'), + ])) + if auth: + rv = '%s@%s' % (auth, rv) + return to_native(rv) + + def encode(self, charset='utf-8', errors='replace'): + """Encodes the URL to a tuple made out of bytes. The charset is + only being used for the path, query and fragment. + """ + return BytesURL( + self.scheme.encode('ascii'), + self.encode_netloc(), + self.path.encode(charset, errors), + self.query.encode(charset, errors), + self.fragment.encode(charset, errors) + ) + + +class BytesURL(BaseURL): + + """Represents a parsed URL in bytes.""" + __slots__ = () + _at = b'@' + _colon = b':' + _lbracket = b'[' + _rbracket = b']' + + def __str__(self): + return self.to_url().decode('utf-8', 'replace') + + def encode_netloc(self): + """Returns the netloc unchanged as bytes.""" + return self.netloc + + def decode(self, charset='utf-8', errors='replace'): + """Decodes the URL to a tuple made out of strings. The charset is + only being used for the path, query and fragment. + """ + return URL( + self.scheme.decode('ascii'), + self.decode_netloc(), + self.path.decode(charset, errors), + self.query.decode(charset, errors), + self.fragment.decode(charset, errors) + ) + + +def _unquote_to_bytes(string, unsafe=''): + if isinstance(string, text_type): + string = string.encode('utf-8') + if isinstance(unsafe, text_type): + unsafe = unsafe.encode('utf-8') + unsafe = frozenset(bytearray(unsafe)) + bits = iter(string.split(b'%')) + result = bytearray(next(bits, b'')) + for item in bits: + try: + char = _hextobyte[item[:2]] + if char in unsafe: + raise KeyError() + result.append(char) + result.extend(item[2:]) + except KeyError: + result.extend(b'%') + result.extend(item) + return bytes(result) + + +def _url_encode_impl(obj, charset, encode_keys, sort, key): + iterable = iter_multi_items(obj) + if sort: + iterable = sorted(iterable, key=key) + for key, value in iterable: + if value is None: + continue + if not isinstance(key, bytes): + key = text_type(key).encode(charset) + if not isinstance(value, bytes): + value = text_type(value).encode(charset) + yield url_quote_plus(key) + '=' + url_quote_plus(value) + + +def _url_unquote_legacy(value, unsafe=''): + try: + return url_unquote(value, charset='utf-8', + errors='strict', unsafe=unsafe) + except UnicodeError: + return url_unquote(value, charset='latin1', unsafe=unsafe) + + +def url_parse(url, scheme=None, allow_fragments=True): + """Parses a URL from a string into a :class:`URL` tuple. If the URL + is lacking a scheme it can be provided as second argument. Otherwise, + it is ignored. Optionally fragments can be stripped from the URL + by setting `allow_fragments` to `False`. + + The inverse of this function is :func:`url_unparse`. + + :param url: the URL to parse. + :param scheme: the default schema to use if the URL is schemaless. + :param allow_fragments: if set to `False` a fragment will be removed + from the URL. + """ + s = make_literal_wrapper(url) + is_text_based = isinstance(url, text_type) + + if scheme is None: + scheme = s('') + netloc = query = fragment = s('') + i = url.find(s(':')) + if i > 0 and _scheme_re.match(to_native(url[:i], errors='replace')): + # make sure "iri" is not actually a port number (in which case + # "scheme" is really part of the path) + rest = url[i + 1:] + if not rest or any(c not in s('0123456789') for c in rest): + # not a port number + scheme, url = url[:i].lower(), rest + + if url[:2] == s('//'): + delim = len(url) + for c in s('/?#'): + wdelim = url.find(c, 2) + if wdelim >= 0: + delim = min(delim, wdelim) + netloc, url = url[2:delim], url[delim:] + if (s('[') in netloc and s(']') not in netloc) or \ + (s(']') in netloc and s('[') not in netloc): + raise ValueError('Invalid IPv6 URL') + + if allow_fragments and s('#') in url: + url, fragment = url.split(s('#'), 1) + if s('?') in url: + url, query = url.split(s('?'), 1) + + result_type = is_text_based and URL or BytesURL + return result_type(scheme, netloc, url, query, fragment) + + +def url_quote(string, charset='utf-8', errors='strict', safe='/:', unsafe=''): + """URL encode a single string with a given encoding. + + :param s: the string to quote. + :param charset: the charset to be used. + :param safe: an optional sequence of safe characters. + :param unsafe: an optional sequence of unsafe characters. + + .. versionadded:: 0.9.2 + The `unsafe` parameter was added. + """ + if not isinstance(string, (text_type, bytes, bytearray)): + string = text_type(string) + if isinstance(string, text_type): + string = string.encode(charset, errors) + if isinstance(safe, text_type): + safe = safe.encode(charset, errors) + if isinstance(unsafe, text_type): + unsafe = unsafe.encode(charset, errors) + safe = frozenset(bytearray(safe) + _always_safe) - frozenset(bytearray(unsafe)) + rv = bytearray() + for char in bytearray(string): + if char in safe: + rv.append(char) + else: + rv.extend(_bytetohex[char]) + return to_native(bytes(rv)) + + +def url_quote_plus(string, charset='utf-8', errors='strict', safe=''): + """URL encode a single string with the given encoding and convert + whitespace to "+". + + :param s: The string to quote. + :param charset: The charset to be used. + :param safe: An optional sequence of safe characters. + """ + return url_quote(string, charset, errors, safe + ' ', '+').replace(' ', '+') + + +def url_unparse(components): + """The reverse operation to :meth:`url_parse`. This accepts arbitrary + as well as :class:`URL` tuples and returns a URL as a string. + + :param components: the parsed URL as tuple which should be converted + into a URL string. + """ + scheme, netloc, path, query, fragment = \ + normalize_string_tuple(components) + s = make_literal_wrapper(scheme) + url = s('') + + # We generally treat file:///x and file:/x the same which is also + # what browsers seem to do. This also allows us to ignore a schema + # register for netloc utilization or having to differenciate between + # empty and missing netloc. + if netloc or (scheme and path.startswith(s('/'))): + if path and path[:1] != s('/'): + path = s('/') + path + url = s('//') + (netloc or s('')) + path + elif path: + url += path + if scheme: + url = scheme + s(':') + url + if query: + url = url + s('?') + query + if fragment: + url = url + s('#') + fragment + return url + + +def url_unquote(string, charset='utf-8', errors='replace', unsafe=''): + """URL decode a single string with a given encoding. If the charset + is set to `None` no unicode decoding is performed and raw bytes + are returned. + + :param s: the string to unquote. + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param errors: the error handling for the charset decoding. + """ + rv = _unquote_to_bytes(string, unsafe) + if charset is not None: + rv = rv.decode(charset, errors) + return rv + + +def url_unquote_plus(s, charset='utf-8', errors='replace'): + """URL decode a single string with the given `charset` and decode "+" to + whitespace. + + Per default encoding errors are ignored. If you want a different behavior + you can set `errors` to ``'replace'`` or ``'strict'``. In strict mode a + :exc:`HTTPUnicodeError` is raised. + + :param s: The string to unquote. + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param errors: The error handling for the `charset` decoding. + """ + if isinstance(s, text_type): + s = s.replace(u'+', u' ') + else: + s = s.replace(b'+', b' ') + return url_unquote(s, charset, errors) + + +def url_fix(s, charset='utf-8'): + r"""Sometimes you get an URL by a user that just isn't a real URL because + it contains unsafe characters like ' ' and so on. This function can fix + some of the problems in a similar way browsers handle data entered by the + user: + + >>> url_fix(u'http://de.wikipedia.org/wiki/Elf (Begriffskl\xe4rung)') + 'http://de.wikipedia.org/wiki/Elf%20(Begriffskl%C3%A4rung)' + + :param s: the string with the URL to fix. + :param charset: The target charset for the URL if the url was given as + unicode string. + """ + # First step is to switch to unicode processing and to convert + # backslashes (which are invalid in URLs anyways) to slashes. This is + # consistent with what Chrome does. + s = to_unicode(s, charset, 'replace').replace('\\', '/') + + # For the specific case that we look like a malformed windows URL + # we want to fix this up manually: + if s.startswith('file://') and s[7:8].isalpha() and s[8:10] in (':/', '|/'): + s = 'file:///' + s[7:] + + url = url_parse(s) + path = url_quote(url.path, charset, safe='/%+$!*\'(),') + qs = url_quote_plus(url.query, charset, safe=':&%=+$!*\'(),') + anchor = url_quote_plus(url.fragment, charset, safe=':&%=+$!*\'(),') + return to_native(url_unparse((url.scheme, url.encode_netloc(), + path, qs, anchor))) + + +def uri_to_iri(uri, charset='utf-8', errors='replace'): + r""" + Converts a URI in a given charset to a IRI. + + Examples for URI versus IRI: + + >>> uri_to_iri(b'http://xn--n3h.net/') + u'http://\u2603.net/' + >>> uri_to_iri(b'http://%C3%BCser:p%C3%A4ssword@xn--n3h.net/p%C3%A5th') + u'http://\xfcser:p\xe4ssword@\u2603.net/p\xe5th' + + Query strings are left unchanged: + + >>> uri_to_iri('/?foo=24&x=%26%2f') + u'/?foo=24&x=%26%2f' + + .. versionadded:: 0.6 + + :param uri: The URI to convert. + :param charset: The charset of the URI. + :param errors: The error handling on decode. + """ + if isinstance(uri, tuple): + uri = url_unparse(uri) + uri = url_parse(to_unicode(uri, charset)) + path = url_unquote(uri.path, charset, errors, '%/;?') + query = url_unquote(uri.query, charset, errors, '%;/?:@&=+,$#') + fragment = url_unquote(uri.fragment, charset, errors, '%;/?:@&=+,$#') + return url_unparse((uri.scheme, uri.decode_netloc(), + path, query, fragment)) + + +def iri_to_uri(iri, charset='utf-8', errors='strict', safe_conversion=False): + r""" + Converts any unicode based IRI to an acceptable ASCII URI. Werkzeug always + uses utf-8 URLs internally because this is what browsers and HTTP do as + well. In some places where it accepts an URL it also accepts a unicode IRI + and converts it into a URI. + + Examples for IRI versus URI: + + >>> iri_to_uri(u'http://☃.net/') + 'http://xn--n3h.net/' + >>> iri_to_uri(u'http://üser:pässword@☃.net/påth') + 'http://%C3%BCser:p%C3%A4ssword@xn--n3h.net/p%C3%A5th' + + There is a general problem with IRI and URI conversion with some + protocols that appear in the wild that are in violation of the URI + specification. In places where Werkzeug goes through a forced IRI to + URI conversion it will set the `safe_conversion` flag which will + not perform a conversion if the end result is already ASCII. This + can mean that the return value is not an entirely correct URI but + it will not destroy such invalid URLs in the process. + + As an example consider the following two IRIs:: + + magnet:?xt=uri:whatever + itms-services://?action=download-manifest + + The internal representation after parsing of those URLs is the same + and there is no way to reconstruct the original one. If safe + conversion is enabled however this function becomes a noop for both of + those strings as they both can be considered URIs. + + .. versionadded:: 0.6 + + .. versionchanged:: 0.9.6 + The `safe_conversion` parameter was added. + + :param iri: The IRI to convert. + :param charset: The charset for the URI. + :param safe_conversion: indicates if a safe conversion should take place. + For more information see the explanation above. + """ + if isinstance(iri, tuple): + iri = url_unparse(iri) + + if safe_conversion: + try: + native_iri = to_native(iri) + ascii_iri = to_native(iri).encode('ascii') + if ascii_iri.split() == [ascii_iri]: + return native_iri + except UnicodeError: + pass + + iri = url_parse(to_unicode(iri, charset, errors)) + + netloc = iri.encode_netloc() + path = url_quote(iri.path, charset, errors, '/:~+%') + query = url_quote(iri.query, charset, errors, '%&[]:;$*()+,!?*/=') + fragment = url_quote(iri.fragment, charset, errors, '=%&[]:;$()+,!?*/') + + return to_native(url_unparse((iri.scheme, netloc, + path, query, fragment))) + + +def url_decode(s, charset='utf-8', decode_keys=False, include_empty=True, + errors='replace', separator='&', cls=None): + """ + Parse a querystring and return it as :class:`MultiDict`. There is a + difference in key decoding on different Python versions. On Python 3 + keys will always be fully decoded whereas on Python 2, keys will + remain bytestrings if they fit into ASCII. On 2.x keys can be forced + to be unicode by setting `decode_keys` to `True`. + + If the charset is set to `None` no unicode decoding will happen and + raw bytes will be returned. + + Per default a missing value for a key will default to an empty key. If + you don't want that behavior you can set `include_empty` to `False`. + + Per default encoding errors are ignored. If you want a different behavior + you can set `errors` to ``'replace'`` or ``'strict'``. In strict mode a + `HTTPUnicodeError` is raised. + + .. versionchanged:: 0.5 + In previous versions ";" and "&" could be used for url decoding. + This changed in 0.5 where only "&" is supported. If you want to + use ";" instead a different `separator` can be provided. + + The `cls` parameter was added. + + :param s: a string with the query string to decode. + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param decode_keys: Used on Python 2.x to control whether keys should + be forced to be unicode objects. If set to `True` + then keys will be unicode in all cases. Otherwise, + they remain `str` if they fit into ASCII. + :param include_empty: Set to `False` if you don't want empty values to + appear in the dict. + :param errors: the decoding error behavior. + :param separator: the pair separator to be used, defaults to ``&`` + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + """ + if cls is None: + cls = MultiDict + if isinstance(s, text_type) and not isinstance(separator, text_type): + separator = separator.decode(charset or 'ascii') + elif isinstance(s, bytes) and not isinstance(separator, bytes): + separator = separator.encode(charset or 'ascii') + return cls(_url_decode_impl(s.split(separator), charset, decode_keys, + include_empty, errors)) + + +def url_decode_stream(stream, charset='utf-8', decode_keys=False, + include_empty=True, errors='replace', separator='&', + cls=None, limit=None, return_iterator=False): + """Works like :func:`url_decode` but decodes a stream. The behavior + of stream and limit follows functions like + :func:`~werkzeug.wsgi.make_line_iter`. The generator of pairs is + directly fed to the `cls` so you can consume the data while it's + parsed. + + .. versionadded:: 0.8 + + :param stream: a stream with the encoded querystring + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param decode_keys: Used on Python 2.x to control whether keys should + be forced to be unicode objects. If set to `True`, + keys will be unicode in all cases. Otherwise, they + remain `str` if they fit into ASCII. + :param include_empty: Set to `False` if you don't want empty values to + appear in the dict. + :param errors: the decoding error behavior. + :param separator: the pair separator to be used, defaults to ``&`` + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + :param limit: the content length of the URL data. Not necessary if + a limited stream is provided. + :param return_iterator: if set to `True` the `cls` argument is ignored + and an iterator over all decoded pairs is + returned + """ + from werkzeug.wsgi import make_chunk_iter + if return_iterator: + cls = lambda x: x + elif cls is None: + cls = MultiDict + pair_iter = make_chunk_iter(stream, separator, limit) + return cls(_url_decode_impl(pair_iter, charset, decode_keys, + include_empty, errors)) + + +def _url_decode_impl(pair_iter, charset, decode_keys, include_empty, errors): + for pair in pair_iter: + if not pair: + continue + s = make_literal_wrapper(pair) + equal = s('=') + if equal in pair: + key, value = pair.split(equal, 1) + else: + if not include_empty: + continue + key = pair + value = s('') + key = url_unquote_plus(key, charset, errors) + if charset is not None and PY2 and not decode_keys: + key = try_coerce_native(key) + yield key, url_unquote_plus(value, charset, errors) + + +def url_encode(obj, charset='utf-8', encode_keys=False, sort=False, key=None, + separator=b'&'): + """URL encode a dict/`MultiDict`. If a value is `None` it will not appear + in the result string. Per default only values are encoded into the target + charset strings. If `encode_keys` is set to ``True`` unicode keys are + supported too. + + If `sort` is set to `True` the items are sorted by `key` or the default + sorting algorithm. + + .. versionadded:: 0.5 + `sort`, `key`, and `separator` were added. + + :param obj: the object to encode into a query string. + :param charset: the charset of the query string. + :param encode_keys: set to `True` if you have unicode keys. (Ignored on + Python 3.x) + :param sort: set to `True` if you want parameters to be sorted by `key`. + :param separator: the separator to be used for the pairs. + :param key: an optional function to be used for sorting. For more details + check out the :func:`sorted` documentation. + """ + separator = to_native(separator, 'ascii') + return separator.join(_url_encode_impl(obj, charset, encode_keys, sort, key)) + + +def url_encode_stream(obj, stream=None, charset='utf-8', encode_keys=False, + sort=False, key=None, separator=b'&'): + """Like :meth:`url_encode` but writes the results to a stream + object. If the stream is `None` a generator over all encoded + pairs is returned. + + .. versionadded:: 0.8 + + :param obj: the object to encode into a query string. + :param stream: a stream to write the encoded object into or `None` if + an iterator over the encoded pairs should be returned. In + that case the separator argument is ignored. + :param charset: the charset of the query string. + :param encode_keys: set to `True` if you have unicode keys. (Ignored on + Python 3.x) + :param sort: set to `True` if you want parameters to be sorted by `key`. + :param separator: the separator to be used for the pairs. + :param key: an optional function to be used for sorting. For more details + check out the :func:`sorted` documentation. + """ + separator = to_native(separator, 'ascii') + gen = _url_encode_impl(obj, charset, encode_keys, sort, key) + if stream is None: + return gen + for idx, chunk in enumerate(gen): + if idx: + stream.write(separator) + stream.write(chunk) + + +def url_join(base, url, allow_fragments=True): + """Join a base URL and a possibly relative URL to form an absolute + interpretation of the latter. + + :param base: the base URL for the join operation. + :param url: the URL to join. + :param allow_fragments: indicates whether fragments should be allowed. + """ + if isinstance(base, tuple): + base = url_unparse(base) + if isinstance(url, tuple): + url = url_unparse(url) + + base, url = normalize_string_tuple((base, url)) + s = make_literal_wrapper(base) + + if not base: + return url + if not url: + return base + + bscheme, bnetloc, bpath, bquery, bfragment = \ + url_parse(base, allow_fragments=allow_fragments) + scheme, netloc, path, query, fragment = \ + url_parse(url, bscheme, allow_fragments) + if scheme != bscheme: + return url + if netloc: + return url_unparse((scheme, netloc, path, query, fragment)) + netloc = bnetloc + + if path[:1] == s('/'): + segments = path.split(s('/')) + elif not path: + segments = bpath.split(s('/')) + if not query: + query = bquery + else: + segments = bpath.split(s('/'))[:-1] + path.split(s('/')) + + # If the rightmost part is "./" we want to keep the slash but + # remove the dot. + if segments[-1] == s('.'): + segments[-1] = s('') + + # Resolve ".." and "." + segments = [segment for segment in segments if segment != s('.')] + while 1: + i = 1 + n = len(segments) - 1 + while i < n: + if segments[i] == s('..') and \ + segments[i - 1] not in (s(''), s('..')): + del segments[i - 1:i + 1] + break + i += 1 + else: + break + + # Remove trailing ".." if the URL is absolute + unwanted_marker = [s(''), s('..')] + while segments[:2] == unwanted_marker: + del segments[1] + + path = s('/').join(segments) + return url_unparse((scheme, netloc, path, query, fragment)) + + +class Href(object): + + """Implements a callable that constructs URLs with the given base. The + function can be called with any number of positional and keyword + arguments which than are used to assemble the URL. Works with URLs + and posix paths. + + Positional arguments are appended as individual segments to + the path of the URL: + + >>> href = Href('/foo') + >>> href('bar', 23) + '/foo/bar/23' + >>> href('foo', bar=23) + '/foo/foo?bar=23' + + If any of the arguments (positional or keyword) evaluates to `None` it + will be skipped. If no keyword arguments are given the last argument + can be a :class:`dict` or :class:`MultiDict` (or any other dict subclass), + otherwise the keyword arguments are used for the query parameters, cutting + off the first trailing underscore of the parameter name: + + >>> href(is_=42) + '/foo?is=42' + >>> href({'foo': 'bar'}) + '/foo?foo=bar' + + Combining of both methods is not allowed: + + >>> href({'foo': 'bar'}, bar=42) + Traceback (most recent call last): + ... + TypeError: keyword arguments and query-dicts can't be combined + + Accessing attributes on the href object creates a new href object with + the attribute name as prefix: + + >>> bar_href = href.bar + >>> bar_href("blub") + '/foo/bar/blub' + + If `sort` is set to `True` the items are sorted by `key` or the default + sorting algorithm: + + >>> href = Href("/", sort=True) + >>> href(a=1, b=2, c=3) + '/?a=1&b=2&c=3' + + .. versionadded:: 0.5 + `sort` and `key` were added. + """ + + def __init__(self, base='./', charset='utf-8', sort=False, key=None): + if not base: + base = './' + self.base = base + self.charset = charset + self.sort = sort + self.key = key + + def __getattr__(self, name): + if name[:2] == '__': + raise AttributeError(name) + base = self.base + if base[-1:] != '/': + base += '/' + return Href(url_join(base, name), self.charset, self.sort, self.key) + + def __call__(self, *path, **query): + if path and isinstance(path[-1], dict): + if query: + raise TypeError('keyword arguments and query-dicts ' + 'can\'t be combined') + query, path = path[-1], path[:-1] + elif query: + query = dict([(k.endswith('_') and k[:-1] or k, v) + for k, v in query.items()]) + path = '/'.join([to_unicode(url_quote(x, self.charset), 'ascii') + for x in path if x is not None]).lstrip('/') + rv = self.base + if path: + if not rv.endswith('/'): + rv += '/' + rv = url_join(rv, './' + path) + if query: + rv += '?' + to_unicode(url_encode(query, self.charset, sort=self.sort, + key=self.key), 'ascii') + return to_native(rv) diff --git a/pyextra/werkzeug/useragents.py b/pyextra/werkzeug/useragents.py new file mode 100644 index 00000000000000..4d7d41f1cf4ebc --- /dev/null +++ b/pyextra/werkzeug/useragents.py @@ -0,0 +1,212 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.useragents + ~~~~~~~~~~~~~~~~~~~ + + This module provides a helper to inspect user agent strings. This module + is far from complete but should work for most of the currently available + browsers. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re + + +class UserAgentParser(object): + + """A simple user agent parser. Used by the `UserAgent`.""" + + platforms = ( + ('cros', 'chromeos'), + ('iphone|ios', 'iphone'), + ('ipad', 'ipad'), + (r'darwin|mac|os\s*x', 'macos'), + ('win', 'windows'), + (r'android', 'android'), + ('netbsd', 'netbsd'), + ('openbsd', 'openbsd'), + ('freebsd', 'freebsd'), + ('dragonfly', 'dragonflybsd'), + ('(sun|i86)os', 'solaris'), + (r'x11|lin(\b|ux)?', 'linux'), + (r'nintendo\s+wii', 'wii'), + ('irix', 'irix'), + ('hp-?ux', 'hpux'), + ('aix', 'aix'), + ('sco|unix_sv', 'sco'), + ('bsd', 'bsd'), + ('amiga', 'amiga'), + ('blackberry|playbook', 'blackberry'), + ('symbian', 'symbian') + ) + browsers = ( + ('googlebot', 'google'), + ('msnbot', 'msn'), + ('yahoo', 'yahoo'), + ('ask jeeves', 'ask'), + (r'aol|america\s+online\s+browser', 'aol'), + ('opera', 'opera'), + ('edge', 'edge'), + ('chrome', 'chrome'), + ('seamonkey', 'seamonkey'), + ('firefox|firebird|phoenix|iceweasel', 'firefox'), + ('galeon', 'galeon'), + ('safari|version', 'safari'), + ('webkit', 'webkit'), + ('camino', 'camino'), + ('konqueror', 'konqueror'), + ('k-meleon', 'kmeleon'), + ('netscape', 'netscape'), + (r'msie|microsoft\s+internet\s+explorer|trident/.+? rv:', 'msie'), + ('lynx', 'lynx'), + ('links', 'links'), + ('Baiduspider', 'baidu'), + ('bingbot', 'bing'), + ('mozilla', 'mozilla') + ) + + _browser_version_re = r'(?:%s)[/\sa-z(]*(\d+[.\da-z]+)?' + _language_re = re.compile( + r'(?:;\s*|\s+)(\b\w{2}\b(?:-\b\w{2}\b)?)\s*;|' + r'(?:\(|\[|;)\s*(\b\w{2}\b(?:-\b\w{2}\b)?)\s*(?:\]|\)|;)' + ) + + def __init__(self): + self.platforms = [(b, re.compile(a, re.I)) for a, b in self.platforms] + self.browsers = [(b, re.compile(self._browser_version_re % a, re.I)) + for a, b in self.browsers] + + def __call__(self, user_agent): + for platform, regex in self.platforms: + match = regex.search(user_agent) + if match is not None: + break + else: + platform = None + for browser, regex in self.browsers: + match = regex.search(user_agent) + if match is not None: + version = match.group(1) + break + else: + browser = version = None + match = self._language_re.search(user_agent) + if match is not None: + language = match.group(1) or match.group(2) + else: + language = None + return platform, browser, version, language + + +class UserAgent(object): + + """Represents a user agent. Pass it a WSGI environment or a user agent + string and you can inspect some of the details from the user agent + string via the attributes. The following attributes exist: + + .. attribute:: string + + the raw user agent string + + .. attribute:: platform + + the browser platform. The following platforms are currently + recognized: + + - `aix` + - `amiga` + - `android` + - `blackberry` + - `bsd` + - `chromeos` + - `dragonflybsd` + - `freebsd` + - `hpux` + - `ipad` + - `iphone` + - `irix` + - `linux` + - `macos` + - `netbsd` + - `openbsd` + - `sco` + - `solaris` + - `symbian` + - `wii` + - `windows` + + .. attribute:: browser + + the name of the browser. The following browsers are currently + recognized: + + - `aol` * + - `ask` * + - `baidu` * + - `bing` * + - `camino` + - `chrome` + - `firefox` + - `galeon` + - `google` * + - `kmeleon` + - `konqueror` + - `links` + - `lynx` + - `mozilla` + - `msie` + - `msn` + - `netscape` + - `opera` + - `safari` + - `seamonkey` + - `webkit` + - `yahoo` * + + (Browsers marked with a star (``*``) are crawlers.) + + .. attribute:: version + + the version of the browser + + .. attribute:: language + + the language of the browser + """ + + _parser = UserAgentParser() + + def __init__(self, environ_or_string): + if isinstance(environ_or_string, dict): + environ_or_string = environ_or_string.get('HTTP_USER_AGENT', '') + self.string = environ_or_string + self.platform, self.browser, self.version, self.language = \ + self._parser(environ_or_string) + + def to_header(self): + return self.string + + def __str__(self): + return self.string + + def __nonzero__(self): + return bool(self.browser) + + __bool__ = __nonzero__ + + def __repr__(self): + return '<%s %r/%s>' % ( + self.__class__.__name__, + self.browser, + self.version + ) + + +# conceptionally this belongs in this module but because we want to lazily +# load the user agent module (which happens in wrappers.py) we have to import +# it afterwards. The class itself has the module set to this module so +# pickle, inspect and similar modules treat the object as if it was really +# implemented here. +from werkzeug.wrappers import UserAgentMixin # noqa diff --git a/pyextra/werkzeug/utils.py b/pyextra/werkzeug/utils.py new file mode 100644 index 00000000000000..918e7e5b60170b --- /dev/null +++ b/pyextra/werkzeug/utils.py @@ -0,0 +1,628 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.utils + ~~~~~~~~~~~~~~ + + This module implements various utilities for WSGI applications. Most of + them are used by the request and response wrappers but especially for + middleware development it makes sense to use them without the wrappers. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re +import os +import sys +import pkgutil +try: + from html.entities import name2codepoint +except ImportError: + from htmlentitydefs import name2codepoint + +from werkzeug._compat import unichr, text_type, string_types, iteritems, \ + reraise, PY2 +from werkzeug._internal import _DictAccessorProperty, \ + _parse_signature, _missing + + +_format_re = re.compile(r'\$(?:(%s)|\{(%s)\})' % (('[a-zA-Z_][a-zA-Z0-9_]*',) * 2)) +_entity_re = re.compile(r'&([^;]+);') +_filename_ascii_strip_re = re.compile(r'[^A-Za-z0-9_.-]') +_windows_device_files = ('CON', 'AUX', 'COM1', 'COM2', 'COM3', 'COM4', 'LPT1', + 'LPT2', 'LPT3', 'PRN', 'NUL') + + +class cached_property(property): + + """A decorator that converts a function into a lazy property. The + function wrapped is called the first time to retrieve the result + and then that calculated result is used the next time you access + the value:: + + class Foo(object): + + @cached_property + def foo(self): + # calculate something important here + return 42 + + The class has to have a `__dict__` in order for this property to + work. + """ + + # implementation detail: A subclass of python's builtin property + # decorator, we override __get__ to check for a cached value. If one + # choses to invoke __get__ by hand the property will still work as + # expected because the lookup logic is replicated in __get__ for + # manual invocation. + + def __init__(self, func, name=None, doc=None): + self.__name__ = name or func.__name__ + self.__module__ = func.__module__ + self.__doc__ = doc or func.__doc__ + self.func = func + + def __set__(self, obj, value): + obj.__dict__[self.__name__] = value + + def __get__(self, obj, type=None): + if obj is None: + return self + value = obj.__dict__.get(self.__name__, _missing) + if value is _missing: + value = self.func(obj) + obj.__dict__[self.__name__] = value + return value + + +class environ_property(_DictAccessorProperty): + + """Maps request attributes to environment variables. This works not only + for the Werzeug request object, but also any other class with an + environ attribute: + + >>> class Test(object): + ... environ = {'key': 'value'} + ... test = environ_property('key') + >>> var = Test() + >>> var.test + 'value' + + If you pass it a second value it's used as default if the key does not + exist, the third one can be a converter that takes a value and converts + it. If it raises :exc:`ValueError` or :exc:`TypeError` the default value + is used. If no default value is provided `None` is used. + + Per default the property is read only. You have to explicitly enable it + by passing ``read_only=False`` to the constructor. + """ + + read_only = True + + def lookup(self, obj): + return obj.environ + + +class header_property(_DictAccessorProperty): + + """Like `environ_property` but for headers.""" + + def lookup(self, obj): + return obj.headers + + +class HTMLBuilder(object): + + """Helper object for HTML generation. + + Per default there are two instances of that class. The `html` one, and + the `xhtml` one for those two dialects. The class uses keyword parameters + and positional parameters to generate small snippets of HTML. + + Keyword parameters are converted to XML/SGML attributes, positional + arguments are used as children. Because Python accepts positional + arguments before keyword arguments it's a good idea to use a list with the + star-syntax for some children: + + >>> html.p(class_='foo', *[html.a('foo', href='foo.html'), ' ', + ... html.a('bar', href='bar.html')]) + u'

    foo bar

    ' + + This class works around some browser limitations and can not be used for + arbitrary SGML/XML generation. For that purpose lxml and similar + libraries exist. + + Calling the builder escapes the string passed: + + >>> html.p(html("")) + u'

    <foo>

    ' + """ + + _entity_re = re.compile(r'&([^;]+);') + _entities = name2codepoint.copy() + _entities['apos'] = 39 + _empty_elements = set([ + 'area', 'base', 'basefont', 'br', 'col', 'command', 'embed', 'frame', + 'hr', 'img', 'input', 'keygen', 'isindex', 'link', 'meta', 'param', + 'source', 'wbr' + ]) + _boolean_attributes = set([ + 'selected', 'checked', 'compact', 'declare', 'defer', 'disabled', + 'ismap', 'multiple', 'nohref', 'noresize', 'noshade', 'nowrap' + ]) + _plaintext_elements = set(['textarea']) + _c_like_cdata = set(['script', 'style']) + + def __init__(self, dialect): + self._dialect = dialect + + def __call__(self, s): + return escape(s) + + def __getattr__(self, tag): + if tag[:2] == '__': + raise AttributeError(tag) + + def proxy(*children, **arguments): + buffer = '<' + tag + for key, value in iteritems(arguments): + if value is None: + continue + if key[-1] == '_': + key = key[:-1] + if key in self._boolean_attributes: + if not value: + continue + if self._dialect == 'xhtml': + value = '="' + key + '"' + else: + value = '' + else: + value = '="' + escape(value) + '"' + buffer += ' ' + key + value + if not children and tag in self._empty_elements: + if self._dialect == 'xhtml': + buffer += ' />' + else: + buffer += '>' + return buffer + buffer += '>' + + children_as_string = ''.join([text_type(x) for x in children + if x is not None]) + + if children_as_string: + if tag in self._plaintext_elements: + children_as_string = escape(children_as_string) + elif tag in self._c_like_cdata and self._dialect == 'xhtml': + children_as_string = '/**/' + buffer += children_as_string + '' + return buffer + return proxy + + def __repr__(self): + return '<%s for %r>' % ( + self.__class__.__name__, + self._dialect + ) + + +html = HTMLBuilder('html') +xhtml = HTMLBuilder('xhtml') + + +def get_content_type(mimetype, charset): + """Returns the full content type string with charset for a mimetype. + + If the mimetype represents text the charset will be appended as charset + parameter, otherwise the mimetype is returned unchanged. + + :param mimetype: the mimetype to be used as content type. + :param charset: the charset to be appended in case it was a text mimetype. + :return: the content type. + """ + if mimetype.startswith('text/') or \ + mimetype == 'application/xml' or \ + (mimetype.startswith('application/') and + mimetype.endswith('+xml')): + mimetype += '; charset=' + charset + return mimetype + + +def format_string(string, context): + """String-template format a string: + + >>> format_string('$foo and ${foo}s', dict(foo=42)) + '42 and 42s' + + This does not do any attribute lookup etc. For more advanced string + formattings have a look at the `werkzeug.template` module. + + :param string: the format string. + :param context: a dict with the variables to insert. + """ + def lookup_arg(match): + x = context[match.group(1) or match.group(2)] + if not isinstance(x, string_types): + x = type(string)(x) + return x + return _format_re.sub(lookup_arg, string) + + +def secure_filename(filename): + r"""Pass it a filename and it will return a secure version of it. This + filename can then safely be stored on a regular file system and passed + to :func:`os.path.join`. The filename returned is an ASCII only string + for maximum portability. + + On windows systems the function also makes sure that the file is not + named after one of the special device files. + + >>> secure_filename("My cool movie.mov") + 'My_cool_movie.mov' + >>> secure_filename("../../../etc/passwd") + 'etc_passwd' + >>> secure_filename(u'i contain cool \xfcml\xe4uts.txt') + 'i_contain_cool_umlauts.txt' + + The function might return an empty filename. It's your responsibility + to ensure that the filename is unique and that you generate random + filename if the function returned an empty one. + + .. versionadded:: 0.5 + + :param filename: the filename to secure + """ + if isinstance(filename, text_type): + from unicodedata import normalize + filename = normalize('NFKD', filename).encode('ascii', 'ignore') + if not PY2: + filename = filename.decode('ascii') + for sep in os.path.sep, os.path.altsep: + if sep: + filename = filename.replace(sep, ' ') + filename = str(_filename_ascii_strip_re.sub('', '_'.join( + filename.split()))).strip('._') + + # on nt a couple of special files are present in each folder. We + # have to ensure that the target file is not such a filename. In + # this case we prepend an underline + if os.name == 'nt' and filename and \ + filename.split('.')[0].upper() in _windows_device_files: + filename = '_' + filename + + return filename + + +def escape(s, quote=None): + """Replace special characters "&", "<", ">" and (") to HTML-safe sequences. + + There is a special handling for `None` which escapes to an empty string. + + .. versionchanged:: 0.9 + `quote` is now implicitly on. + + :param s: the string to escape. + :param quote: ignored. + """ + if s is None: + return '' + elif hasattr(s, '__html__'): + return text_type(s.__html__()) + elif not isinstance(s, string_types): + s = text_type(s) + if quote is not None: + from warnings import warn + warn(DeprecationWarning('quote parameter is implicit now'), stacklevel=2) + s = s.replace('&', '&').replace('<', '<') \ + .replace('>', '>').replace('"', """) + return s + + +def unescape(s): + """The reverse function of `escape`. This unescapes all the HTML + entities, not only the XML entities inserted by `escape`. + + :param s: the string to unescape. + """ + def handle_match(m): + name = m.group(1) + if name in HTMLBuilder._entities: + return unichr(HTMLBuilder._entities[name]) + try: + if name[:2] in ('#x', '#X'): + return unichr(int(name[2:], 16)) + elif name.startswith('#'): + return unichr(int(name[1:])) + except ValueError: + pass + return u'' + return _entity_re.sub(handle_match, s) + + +def redirect(location, code=302, Response=None): + """Returns a response object (a WSGI application) that, if called, + redirects the client to the target location. Supported codes are 301, + 302, 303, 305, and 307. 300 is not supported because it's not a real + redirect and 304 because it's the answer for a request with a request + with defined If-Modified-Since headers. + + .. versionadded:: 0.6 + The location can now be a unicode string that is encoded using + the :func:`iri_to_uri` function. + + .. versionadded:: 0.10 + The class used for the Response object can now be passed in. + + :param location: the location the response should redirect to. + :param code: the redirect status code. defaults to 302. + :param class Response: a Response class to use when instantiating a + response. The default is :class:`werkzeug.wrappers.Response` if + unspecified. + """ + if Response is None: + from werkzeug.wrappers import Response + + display_location = escape(location) + if isinstance(location, text_type): + # Safe conversion is necessary here as we might redirect + # to a broken URI scheme (for instance itms-services). + from werkzeug.urls import iri_to_uri + location = iri_to_uri(location, safe_conversion=True) + response = Response( + '\n' + 'Redirecting...\n' + '

    Redirecting...

    \n' + '

    You should be redirected automatically to target URL: ' + '%s. If not click the link.' % + (escape(location), display_location), code, mimetype='text/html') + response.headers['Location'] = location + return response + + +def append_slash_redirect(environ, code=301): + """Redirects to the same URL but with a slash appended. The behavior + of this function is undefined if the path ends with a slash already. + + :param environ: the WSGI environment for the request that triggers + the redirect. + :param code: the status code for the redirect. + """ + new_path = environ['PATH_INFO'].strip('/') + '/' + query_string = environ.get('QUERY_STRING') + if query_string: + new_path += '?' + query_string + return redirect(new_path, code) + + +def import_string(import_name, silent=False): + """Imports an object based on a string. This is useful if you want to + use import paths as endpoints or something similar. An import path can + be specified either in dotted notation (``xml.sax.saxutils.escape``) + or with a colon as object delimiter (``xml.sax.saxutils:escape``). + + If `silent` is True the return value will be `None` if the import fails. + + :param import_name: the dotted name for the object to import. + :param silent: if set to `True` import errors are ignored and + `None` is returned instead. + :return: imported object + """ + # force the import name to automatically convert to strings + # __import__ is not able to handle unicode strings in the fromlist + # if the module is a package + import_name = str(import_name).replace(':', '.') + try: + try: + __import__(import_name) + except ImportError: + if '.' not in import_name: + raise + else: + return sys.modules[import_name] + + module_name, obj_name = import_name.rsplit('.', 1) + try: + module = __import__(module_name, None, None, [obj_name]) + except ImportError: + # support importing modules not yet set up by the parent module + # (or package for that matter) + module = import_string(module_name) + + try: + return getattr(module, obj_name) + except AttributeError as e: + raise ImportError(e) + + except ImportError as e: + if not silent: + reraise( + ImportStringError, + ImportStringError(import_name, e), + sys.exc_info()[2]) + + +def find_modules(import_path, include_packages=False, recursive=False): + """Finds all the modules below a package. This can be useful to + automatically import all views / controllers so that their metaclasses / + function decorators have a chance to register themselves on the + application. + + Packages are not returned unless `include_packages` is `True`. This can + also recursively list modules but in that case it will import all the + packages to get the correct load path of that module. + + :param import_path: the dotted name for the package to find child modules. + :param include_packages: set to `True` if packages should be returned, too. + :param recursive: set to `True` if recursion should happen. + :return: generator + """ + module = import_string(import_path) + path = getattr(module, '__path__', None) + if path is None: + raise ValueError('%r is not a package' % import_path) + basename = module.__name__ + '.' + for importer, modname, ispkg in pkgutil.iter_modules(path): + modname = basename + modname + if ispkg: + if include_packages: + yield modname + if recursive: + for item in find_modules(modname, include_packages, True): + yield item + else: + yield modname + + +def validate_arguments(func, args, kwargs, drop_extra=True): + """Checks if the function accepts the arguments and keyword arguments. + Returns a new ``(args, kwargs)`` tuple that can safely be passed to + the function without causing a `TypeError` because the function signature + is incompatible. If `drop_extra` is set to `True` (which is the default) + any extra positional or keyword arguments are dropped automatically. + + The exception raised provides three attributes: + + `missing` + A set of argument names that the function expected but where + missing. + + `extra` + A dict of keyword arguments that the function can not handle but + where provided. + + `extra_positional` + A list of values that where given by positional argument but the + function cannot accept. + + This can be useful for decorators that forward user submitted data to + a view function:: + + from werkzeug.utils import ArgumentValidationError, validate_arguments + + def sanitize(f): + def proxy(request): + data = request.values.to_dict() + try: + args, kwargs = validate_arguments(f, (request,), data) + except ArgumentValidationError: + raise BadRequest('The browser failed to transmit all ' + 'the data expected.') + return f(*args, **kwargs) + return proxy + + :param func: the function the validation is performed against. + :param args: a tuple of positional arguments. + :param kwargs: a dict of keyword arguments. + :param drop_extra: set to `False` if you don't want extra arguments + to be silently dropped. + :return: tuple in the form ``(args, kwargs)``. + """ + parser = _parse_signature(func) + args, kwargs, missing, extra, extra_positional = parser(args, kwargs)[:5] + if missing: + raise ArgumentValidationError(tuple(missing)) + elif (extra or extra_positional) and not drop_extra: + raise ArgumentValidationError(None, extra, extra_positional) + return tuple(args), kwargs + + +def bind_arguments(func, args, kwargs): + """Bind the arguments provided into a dict. When passed a function, + a tuple of arguments and a dict of keyword arguments `bind_arguments` + returns a dict of names as the function would see it. This can be useful + to implement a cache decorator that uses the function arguments to build + the cache key based on the values of the arguments. + + :param func: the function the arguments should be bound for. + :param args: tuple of positional arguments. + :param kwargs: a dict of keyword arguments. + :return: a :class:`dict` of bound keyword arguments. + """ + args, kwargs, missing, extra, extra_positional, \ + arg_spec, vararg_var, kwarg_var = _parse_signature(func)(args, kwargs) + values = {} + for (name, has_default, default), value in zip(arg_spec, args): + values[name] = value + if vararg_var is not None: + values[vararg_var] = tuple(extra_positional) + elif extra_positional: + raise TypeError('too many positional arguments') + if kwarg_var is not None: + multikw = set(extra) & set([x[0] for x in arg_spec]) + if multikw: + raise TypeError('got multiple values for keyword argument ' + + repr(next(iter(multikw)))) + values[kwarg_var] = extra + elif extra: + raise TypeError('got unexpected keyword argument ' + + repr(next(iter(extra)))) + return values + + +class ArgumentValidationError(ValueError): + + """Raised if :func:`validate_arguments` fails to validate""" + + def __init__(self, missing=None, extra=None, extra_positional=None): + self.missing = set(missing or ()) + self.extra = extra or {} + self.extra_positional = extra_positional or [] + ValueError.__init__(self, 'function arguments invalid. (' + '%d missing, %d additional)' % ( + len(self.missing), + len(self.extra) + len(self.extra_positional) + )) + + +class ImportStringError(ImportError): + + """Provides information about a failed :func:`import_string` attempt.""" + + #: String in dotted notation that failed to be imported. + import_name = None + #: Wrapped exception. + exception = None + + def __init__(self, import_name, exception): + self.import_name = import_name + self.exception = exception + + msg = ( + 'import_string() failed for %r. Possible reasons are:\n\n' + '- missing __init__.py in a package;\n' + '- package or module path not included in sys.path;\n' + '- duplicated package or module name taking precedence in ' + 'sys.path;\n' + '- missing module, class, function or variable;\n\n' + 'Debugged import:\n\n%s\n\n' + 'Original exception:\n\n%s: %s') + + name = '' + tracked = [] + for part in import_name.replace(':', '.').split('.'): + name += (name and '.') + part + imported = import_string(name, silent=True) + if imported: + tracked.append((name, getattr(imported, '__file__', None))) + else: + track = ['- %r found in %r.' % (n, i) for n, i in tracked] + track.append('- %r not found.' % name) + msg = msg % (import_name, '\n'.join(track), + exception.__class__.__name__, str(exception)) + break + + ImportError.__init__(self, msg) + + def __repr__(self): + return '<%s(%r, %r)>' % (self.__class__.__name__, self.import_name, + self.exception) + + +# DEPRECATED +# these objects were previously in this module as well. we import +# them here for backwards compatibility with old pickles. +from werkzeug.datastructures import ( # noqa + MultiDict, CombinedMultiDict, Headers, EnvironHeaders) +from werkzeug.http import parse_cookie, dump_cookie # noqa diff --git a/pyextra/werkzeug/websocket.py b/pyextra/werkzeug/websocket.py new file mode 100644 index 00000000000000..764698b70337ea --- /dev/null +++ b/pyextra/werkzeug/websocket.py @@ -0,0 +1,337 @@ +import re +import errno +import socket +import struct +import collections + +from base64 import b64decode, b64encode +from hashlib import sha1 + + +WS_KEY = b'258EAFA5-E914-47DA-95CA-C5AB0DC85B11' + + +def pack_message(message): + """Pack the message inside ``00`` and ``FF`` + As per the dataframing section (5.3) for the websocket spec + """ + if isinstance(message, unicode): + message = message.encode('utf-8') + elif not isinstance(message, str): + message = str(message) + packed = "\x00%s\xFF" % message + return packed + + +def encode_hybi(buf, opcode, base64=False): + """ Encode a HyBi style WebSocket frame. + Optional opcode: + 0x0 - continuation + 0x1 - text frame (base64 encode buf) + 0x2 - binary frame (use raw buf) + 0x8 - connection close + 0x9 - ping + 0xA - pong + """ + if base64: + buf = b64encode(buf) + b1 = 0x80 | (opcode & 0x0f) # FIN + opcode + payload_len = len(buf) + if payload_len <= 125: + header = struct.pack('>BB', b1, payload_len) + elif payload_len > 125 and payload_len < 65536: + header = struct.pack('>BBH', b1, 126, payload_len) + elif payload_len >= 65536: + header = struct.pack('>BBQ', b1, 127, payload_len) + return header + buf, len(header), 0 + + +def decode_hybi(buf, base64=False): + """Decode HyBi style WebSocket packets.""" + f = {'fin' : 0, + 'opcode' : 0, + 'mask' : 0, + 'hlen' : 2, + 'length' : 0, + 'payload' : None, + 'left' : 0, + 'close_code' : None, + 'close_reason' : None} + + blen = len(buf) + f['left'] = blen + + if blen < f['hlen']: + return f # Incomplete frame header + + b1, b2 = struct.unpack_from(">BB", buf) + f['opcode'] = b1 & 0x0f + f['fin'] = (b1 & 0x80) >> 7 + has_mask = (b2 & 0x80) >> 7 + + f['length'] = b2 & 0x7f + + if f['length'] == 126: + f['hlen'] = 4 + if blen < f['hlen']: + return f # Incomplete frame header + (f['length'],) = struct.unpack_from('>xxH', buf) + elif f['length'] == 127: + f['hlen'] = 10 + if blen < f['hlen']: + return f # Incomplete frame header + (f['length'],) = struct.unpack_from('>xxQ', buf) + + full_len = f['hlen'] + has_mask * 4 + f['length'] + + if blen < full_len: # Incomplete frame + return f # Incomplete frame header + + # Number of bytes that are part of the next frame(s) + f['left'] = blen - full_len + + # Process 1 frame + if has_mask: + # unmask payload + f['mask'] = buf[f['hlen']:f['hlen']+4] + b = c = '' + if f['length'] >= 4: + data = struct.unpack('= 2: + f['close_code'] = struct.unpack_from(">H", f['payload']) + if f['length'] > 3: + f['close_reason'] = f['payload'][2:] + + return f + + +class WebSocketWSGI(object): + + def __init__(self, handler): + self.handler = handler + + def verify_client(self, ws): + pass + + def __call__(self, environ, start_response): + if not (environ.get('HTTP_CONNECTION').find('Upgrade') != -1 and + environ['HTTP_UPGRADE'].lower() == 'websocket'): + # need to check a few more things here for true compliance + start_response('400 Bad Request', [('Connection','close')]) + return [] + + sock = environ['gunicorn.socket'] + + ws = WebSocket(sock, environ) + + handshake_reply = ("HTTP/1.1 101 Switching Protocols\r\n" + "Upgrade: websocket\r\n" + "Connection: Upgrade\r\n") + + path = environ['PATH_INFO'] + key = environ.get('HTTP_SEC_WEBSOCKET_KEY') + if key: + ws_key = b64decode(key) + if len(ws_key) != 16: + start_response('400 Bad Request', [('Connection','close')]) + return [] + + protocols = [] + subprotocols = environ.get('HTTP_SEC_WEBSOCKET_PROTOCOL') + ws_protocols = [] + if subprotocols: + for s in subprotocols.split(','): + s = s.strip() + if s in protocols: + ws_protocols.append(s) + if ws_protocols: + handshake_reply += 'Sec-WebSocket-Protocol: %s\r\n' % ', '.join(ws_protocols) + + exts = [] + extensions = environ.get('HTTP_SEC_WEBSOCKET_EXTENSIONS') + ws_extensions = [] + if extensions: + for ext in extensions.split(','): + ext = ext.strip() + if ext in exts: + ws_extensions.append(ext) + if ws_extensions: + handshake_reply += 'Sec-WebSocket-Extensions: %s\r\n' % ', '.join(ws_extensions) + + handshake_reply += ( + "Sec-WebSocket-Origin: %s\r\n" + "Sec-WebSocket-Location: ws://%s%s\r\n" + "Sec-WebSocket-Version: %s\r\n" + "Sec-WebSocket-Accept: %s\r\n\r\n" + % ( + environ.get('HTTP_ORIGIN'), + environ.get('HTTP_HOST'), + path, + ws.version, + b64encode(sha1(key + WS_KEY).digest()) + )) + + else: + + handshake_reply += ( + "WebSocket-Origin: %s\r\n" + "WebSocket-Location: ws://%s%s\r\n\r\n" % ( + environ.get('HTTP_ORIGIN'), + environ.get('HTTP_HOST'), + path)) + + sock.sendall(handshake_reply) + + try: + self.handler(ws) + except socket.error as e: + if e[0] != errno.EPIPE: + raise + + # use this undocumented feature of grainbows to ensure that it + # doesn't barf on the fact that we didn't call start_response + return ALREADY_HANDLED + + +class WebSocket(object): + + def __init__(self, sock, environ, version=76): + self._socket = sock + try: + version = int(environ.get('HTTP_SEC_WEBSOCKET_VERSION')) + except (ValueError, TypeError): + version = 76 + self.version = version + self.closed = False + self.accepted = False + self._buf = b'' + self._msgs = collections.deque() + + def _parse_messages(self): + """ Parses for messages in the buffer *buf*. It is assumed that + the buffer contains the start character for a message, but that it + may contain only part of the rest of the message. + Returns an array of messages, and the buffer remainder that + didn't contain any full messages.""" + msgs = [] + end_idx = 0 + buf = self._buf + while buf: + if self.version in (7, 8, 13): + frame = decode_hybi(buf, base64=False) + + if frame['payload'] == None: + break + else: + if frame['opcode'] == 0x8: # connection close + self.closed = True + break + else: + msgs.append(frame['payload']); + if frame['left']: + buf = buf[-frame['left']:] + else: + buf = b'' + + else: + frame_type = ord(buf[0]) + if frame_type == 0: + # Normal message. + end_idx = buf.find("\xFF") + if end_idx == -1: #pragma NO COVER + break + msgs.append(buf[1:end_idx].decode('utf-8', 'replace')) + buf = buf[end_idx+1:] + elif frame_type == 255: + # Closing handshake. + assert ord(buf[1]) == 0, "Unexpected closing handshake: %r" % buf + self.closed = True + break + else: + raise ValueError("Don't understand how to parse this type of message: %r" % buf) + self._buf = buf + return msgs + + def send(self, message): + """Send a message to the browser. + *message* should be convertable to a string; unicode objects should be + encodable as utf-8. Raises socket.error with errno of 32 + (broken pipe) if the socket has already been closed by the client. + """ + if self.version in (7, 8, 13): + packed, lenhead, lentail = encode_hybi( + message, opcode=0x01, base64=False) + else: + packed = pack_message(message) + self._socket.sendall(packed) + + def wait(self): + """Waits for and deserializes messages. + Returns a single message; the oldest not yet processed. If the client + has already closed the connection, returns None. This is different + from normal socket behavior because the empty string is a valid + websocket message.""" + while not self._msgs: + # Websocket might be closed already. + if self.closed: + return None + # no parsed messages, must mean buf needs more data + delta = self._socket.recv(8096) + if delta == '': + return None + self._buf += delta + msgs = self._parse_messages() + self._msgs.extend(msgs) + return self._msgs.popleft() + + def _send_closing_frame(self, ignore_send_errors=False): + """Sends the closing frame to the client, if required.""" + if self.version in (7, 8, 13) and not self.closed: + msg = '' + #if code != None: + # msg = struct.pack(">H%ds" % (len(reason)), code) + + buf, h, t = encode_hybi(msg, opcode=0x08, base64=False) + self._socket.sendall(buf) + self.closed = True + + elif self.version == 76 and not self.closed: + try: + self._socket.sendall("\xff\x00") + except socket.error: + # Sometimes, like when the remote side cuts off the connection, + # we don't care about this. + if not ignore_send_errors: #pragma NO COVER + raise + self.closed = True + + def close(self): + """Forcibly close the websocket; generally it is preferable to + return from the handler method.""" + self._send_closing_frame() + self._socket.shutdown(True) + self._socket.close() diff --git a/pyextra/werkzeug/wrappers.py b/pyextra/werkzeug/wrappers.py new file mode 100644 index 00000000000000..92dfa5dacc0dcb --- /dev/null +++ b/pyextra/werkzeug/wrappers.py @@ -0,0 +1,2028 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.wrappers + ~~~~~~~~~~~~~~~~~ + + The wrappers are simple request and response objects which you can + subclass to do whatever you want them to do. The request object contains + the information transmitted by the client (webbrowser) and the response + object contains all the information sent back to the browser. + + An important detail is that the request object is created with the WSGI + environ and will act as high-level proxy whereas the response object is an + actual WSGI application. + + Like everything else in Werkzeug these objects will work correctly with + unicode data. Incoming form data parsed by the response object will be + decoded into an unicode object if possible and if it makes sense. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +from functools import update_wrapper +from datetime import datetime, timedelta +from warnings import warn + +from werkzeug.http import HTTP_STATUS_CODES, \ + parse_accept_header, parse_cache_control_header, parse_etags, \ + parse_date, generate_etag, is_resource_modified, unquote_etag, \ + quote_etag, parse_set_header, parse_authorization_header, \ + parse_www_authenticate_header, remove_entity_headers, \ + parse_options_header, dump_options_header, http_date, \ + parse_if_range_header, parse_cookie, dump_cookie, \ + parse_range_header, parse_content_range_header, dump_header, \ + parse_age, dump_age +from werkzeug.urls import url_decode, iri_to_uri, url_join +from werkzeug.formparser import FormDataParser, default_stream_factory +from werkzeug.utils import cached_property, environ_property, \ + header_property, get_content_type +from werkzeug.wsgi import get_current_url, get_host, \ + ClosingIterator, get_input_stream, get_content_length, _RangeWrapper +from werkzeug.datastructures import MultiDict, CombinedMultiDict, Headers, \ + EnvironHeaders, ImmutableMultiDict, ImmutableTypeConversionDict, \ + ImmutableList, MIMEAccept, CharsetAccept, LanguageAccept, \ + ResponseCacheControl, RequestCacheControl, CallbackDict, \ + ContentRange, iter_multi_items +from werkzeug._internal import _get_environ +from werkzeug._compat import to_bytes, string_types, text_type, \ + integer_types, wsgi_decoding_dance, wsgi_get_bytes, \ + to_unicode, to_native, BytesIO + + +def _run_wsgi_app(*args): + """This function replaces itself to ensure that the test module is not + imported unless required. DO NOT USE! + """ + global _run_wsgi_app + from werkzeug.test import run_wsgi_app as _run_wsgi_app + return _run_wsgi_app(*args) + + +def _warn_if_string(iterable): + """Helper for the response objects to check if the iterable returned + to the WSGI server is not a string. + """ + if isinstance(iterable, string_types): + warn(Warning('response iterable was set to a string. This appears ' + 'to work but means that the server will send the ' + 'data to the client char, by char. This is almost ' + 'never intended behavior, use response.data to assign ' + 'strings to the response object.'), stacklevel=2) + + +def _assert_not_shallow(request): + if request.shallow: + raise RuntimeError('A shallow request tried to consume ' + 'form data. If you really want to do ' + 'that, set `shallow` to False.') + + +def _iter_encoded(iterable, charset): + for item in iterable: + if isinstance(item, text_type): + yield item.encode(charset) + else: + yield item + + +def _clean_accept_ranges(accept_ranges): + if accept_ranges is True: + return "bytes" + elif accept_ranges is False: + return "none" + elif isinstance(accept_ranges, text_type): + return to_native(accept_ranges) + raise ValueError("Invalid accept_ranges value") + + +class BaseRequest(object): + + """Very basic request object. This does not implement advanced stuff like + entity tag parsing or cache controls. The request object is created with + the WSGI environment as first argument and will add itself to the WSGI + environment as ``'werkzeug.request'`` unless it's created with + `populate_request` set to False. + + There are a couple of mixins available that add additional functionality + to the request object, there is also a class called `Request` which + subclasses `BaseRequest` and all the important mixins. + + It's a good idea to create a custom subclass of the :class:`BaseRequest` + and add missing functionality either via mixins or direct implementation. + Here an example for such subclasses:: + + from werkzeug.wrappers import BaseRequest, ETagRequestMixin + + class Request(BaseRequest, ETagRequestMixin): + pass + + Request objects are **read only**. As of 0.5 modifications are not + allowed in any place. Unlike the lower level parsing functions the + request object will use immutable objects everywhere possible. + + Per default the request object will assume all the text data is `utf-8` + encoded. Please refer to `the unicode chapter `_ for more + details about customizing the behavior. + + Per default the request object will be added to the WSGI + environment as `werkzeug.request` to support the debugging system. + If you don't want that, set `populate_request` to `False`. + + If `shallow` is `True` the environment is initialized as shallow + object around the environ. Every operation that would modify the + environ in any way (such as consuming form data) raises an exception + unless the `shallow` attribute is explicitly set to `False`. This + is useful for middlewares where you don't want to consume the form + data by accident. A shallow request is not populated to the WSGI + environment. + + .. versionchanged:: 0.5 + read-only mode was enforced by using immutables classes for all + data. + """ + + #: the charset for the request, defaults to utf-8 + charset = 'utf-8' + + #: the error handling procedure for errors, defaults to 'replace' + encoding_errors = 'replace' + + #: the maximum content length. This is forwarded to the form data + #: parsing function (:func:`parse_form_data`). When set and the + #: :attr:`form` or :attr:`files` attribute is accessed and the + #: parsing fails because more than the specified value is transmitted + #: a :exc:`~werkzeug.exceptions.RequestEntityTooLarge` exception is raised. + #: + #: Have a look at :ref:`dealing-with-request-data` for more details. + #: + #: .. versionadded:: 0.5 + max_content_length = None + + #: the maximum form field size. This is forwarded to the form data + #: parsing function (:func:`parse_form_data`). When set and the + #: :attr:`form` or :attr:`files` attribute is accessed and the + #: data in memory for post data is longer than the specified value a + #: :exc:`~werkzeug.exceptions.RequestEntityTooLarge` exception is raised. + #: + #: Have a look at :ref:`dealing-with-request-data` for more details. + #: + #: .. versionadded:: 0.5 + max_form_memory_size = None + + #: the class to use for `args` and `form`. The default is an + #: :class:`~werkzeug.datastructures.ImmutableMultiDict` which supports + #: multiple values per key. alternatively it makes sense to use an + #: :class:`~werkzeug.datastructures.ImmutableOrderedMultiDict` which + #: preserves order or a :class:`~werkzeug.datastructures.ImmutableDict` + #: which is the fastest but only remembers the last key. It is also + #: possible to use mutable structures, but this is not recommended. + #: + #: .. versionadded:: 0.6 + parameter_storage_class = ImmutableMultiDict + + #: the type to be used for list values from the incoming WSGI environment. + #: By default an :class:`~werkzeug.datastructures.ImmutableList` is used + #: (for example for :attr:`access_list`). + #: + #: .. versionadded:: 0.6 + list_storage_class = ImmutableList + + #: the type to be used for dict values from the incoming WSGI environment. + #: By default an + #: :class:`~werkzeug.datastructures.ImmutableTypeConversionDict` is used + #: (for example for :attr:`cookies`). + #: + #: .. versionadded:: 0.6 + dict_storage_class = ImmutableTypeConversionDict + + #: The form data parser that shoud be used. Can be replaced to customize + #: the form date parsing. + form_data_parser_class = FormDataParser + + #: Optionally a list of hosts that is trusted by this request. By default + #: all hosts are trusted which means that whatever the client sends the + #: host is will be accepted. + #: + #: This is the recommended setup as a webserver should manually be set up + #: to only route correct hosts to the application, and remove the + #: `X-Forwarded-Host` header if it is not being used (see + #: :func:`werkzeug.wsgi.get_host`). + #: + #: .. versionadded:: 0.9 + trusted_hosts = None + + #: Indicates whether the data descriptor should be allowed to read and + #: buffer up the input stream. By default it's enabled. + #: + #: .. versionadded:: 0.9 + disable_data_descriptor = False + + def __init__(self, environ, populate_request=True, shallow=False): + self.environ = environ + if populate_request and not shallow: + self.environ['werkzeug.request'] = self + self.shallow = shallow + + def __repr__(self): + # make sure the __repr__ even works if the request was created + # from an invalid WSGI environment. If we display the request + # in a debug session we don't want the repr to blow up. + args = [] + try: + args.append("'%s'" % to_native(self.url, self.url_charset)) + args.append('[%s]' % self.method) + except Exception: + args.append('(invalid WSGI environ)') + + return '<%s %s>' % ( + self.__class__.__name__, + ' '.join(args) + ) + + @property + def url_charset(self): + """The charset that is assumed for URLs. Defaults to the value + of :attr:`charset`. + + .. versionadded:: 0.6 + """ + return self.charset + + @classmethod + def from_values(cls, *args, **kwargs): + """Create a new request object based on the values provided. If + environ is given missing values are filled from there. This method is + useful for small scripts when you need to simulate a request from an URL. + Do not use this method for unittesting, there is a full featured client + object (:class:`Client`) that allows to create multipart requests, + support for cookies etc. + + This accepts the same options as the + :class:`~werkzeug.test.EnvironBuilder`. + + .. versionchanged:: 0.5 + This method now accepts the same arguments as + :class:`~werkzeug.test.EnvironBuilder`. Because of this the + `environ` parameter is now called `environ_overrides`. + + :return: request object + """ + from werkzeug.test import EnvironBuilder + charset = kwargs.pop('charset', cls.charset) + kwargs['charset'] = charset + builder = EnvironBuilder(*args, **kwargs) + try: + return builder.get_request(cls) + finally: + builder.close() + + @classmethod + def application(cls, f): + """Decorate a function as responder that accepts the request as first + argument. This works like the :func:`responder` decorator but the + function is passed the request object as first argument and the + request object will be closed automatically:: + + @Request.application + def my_wsgi_app(request): + return Response('Hello World!') + + As of Werkzeug 0.14 HTTP exceptions are automatically caught and + converted to responses instead of failing. + + :param f: the WSGI callable to decorate + :return: a new WSGI callable + """ + #: return a callable that wraps the -2nd argument with the request + #: and calls the function with all the arguments up to that one and + #: the request. The return value is then called with the latest + #: two arguments. This makes it possible to use this decorator for + #: both methods and standalone WSGI functions. + from werkzeug.exceptions import HTTPException + + def application(*args): + request = cls(args[-2]) + with request: + try: + resp = f(*args[:-2] + (request,)) + except HTTPException as e: + resp = e.get_response(args[-2]) + return resp(*args[-2:]) + + return update_wrapper(application, f) + + def _get_file_stream(self, total_content_length, content_type, filename=None, + content_length=None): + """Called to get a stream for the file upload. + + This must provide a file-like class with `read()`, `readline()` + and `seek()` methods that is both writeable and readable. + + The default implementation returns a temporary file if the total + content length is higher than 500KB. Because many browsers do not + provide a content length for the files only the total content + length matters. + + :param total_content_length: the total content length of all the + data in the request combined. This value + is guaranteed to be there. + :param content_type: the mimetype of the uploaded file. + :param filename: the filename of the uploaded file. May be `None`. + :param content_length: the length of this file. This value is usually + not provided because webbrowsers do not provide + this value. + """ + return default_stream_factory( + total_content_length=total_content_length, + content_type=content_type, + filename=filename, + content_length=content_length) + + @property + def want_form_data_parsed(self): + """Returns True if the request method carries content. As of + Werkzeug 0.9 this will be the case if a content type is transmitted. + + .. versionadded:: 0.8 + """ + return bool(self.environ.get('CONTENT_TYPE')) + + def make_form_data_parser(self): + """Creates the form data parser. Instantiates the + :attr:`form_data_parser_class` with some parameters. + + .. versionadded:: 0.8 + """ + return self.form_data_parser_class(self._get_file_stream, + self.charset, + self.encoding_errors, + self.max_form_memory_size, + self.max_content_length, + self.parameter_storage_class) + + def _load_form_data(self): + """Method used internally to retrieve submitted data. After calling + this sets `form` and `files` on the request object to multi dicts + filled with the incoming form data. As a matter of fact the input + stream will be empty afterwards. You can also call this method to + force the parsing of the form data. + + .. versionadded:: 0.8 + """ + # abort early if we have already consumed the stream + if 'form' in self.__dict__: + return + + _assert_not_shallow(self) + + if self.want_form_data_parsed: + content_type = self.environ.get('CONTENT_TYPE', '') + content_length = get_content_length(self.environ) + mimetype, options = parse_options_header(content_type) + parser = self.make_form_data_parser() + data = parser.parse(self._get_stream_for_parsing(), + mimetype, content_length, options) + else: + data = (self.stream, self.parameter_storage_class(), + self.parameter_storage_class()) + + # inject the values into the instance dict so that we bypass + # our cached_property non-data descriptor. + d = self.__dict__ + d['stream'], d['form'], d['files'] = data + + def _get_stream_for_parsing(self): + """This is the same as accessing :attr:`stream` with the difference + that if it finds cached data from calling :meth:`get_data` first it + will create a new stream out of the cached data. + + .. versionadded:: 0.9.3 + """ + cached_data = getattr(self, '_cached_data', None) + if cached_data is not None: + return BytesIO(cached_data) + return self.stream + + def close(self): + """Closes associated resources of this request object. This + closes all file handles explicitly. You can also use the request + object in a with statement which will automatically close it. + + .. versionadded:: 0.9 + """ + files = self.__dict__.get('files') + for key, value in iter_multi_items(files or ()): + value.close() + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close() + + @cached_property + def stream(self): + """ + If the incoming form data was not encoded with a known mimetype + the data is stored unmodified in this stream for consumption. Most + of the time it is a better idea to use :attr:`data` which will give + you that data as a string. The stream only returns the data once. + + Unlike :attr:`input_stream` this stream is properly guarded that you + can't accidentally read past the length of the input. Werkzeug will + internally always refer to this stream to read data which makes it + possible to wrap this object with a stream that does filtering. + + .. versionchanged:: 0.9 + This stream is now always available but might be consumed by the + form parser later on. Previously the stream was only set if no + parsing happened. + """ + _assert_not_shallow(self) + return get_input_stream(self.environ) + + input_stream = environ_property('wsgi.input', """ + The WSGI input stream. + + In general it's a bad idea to use this one because you can easily read past + the boundary. Use the :attr:`stream` instead. + """) + + @cached_property + def args(self): + """The parsed URL parameters (the part in the URL after the question + mark). + + By default an + :class:`~werkzeug.datastructures.ImmutableMultiDict` + is returned from this function. This can be changed by setting + :attr:`parameter_storage_class` to a different type. This might + be necessary if the order of the form data is important. + """ + return url_decode(wsgi_get_bytes(self.environ.get('QUERY_STRING', '')), + self.url_charset, errors=self.encoding_errors, + cls=self.parameter_storage_class) + + @cached_property + def data(self): + """ + Contains the incoming request data as string in case it came with + a mimetype Werkzeug does not handle. + """ + + if self.disable_data_descriptor: + raise AttributeError('data descriptor is disabled') + # XXX: this should eventually be deprecated. + + # We trigger form data parsing first which means that the descriptor + # will not cache the data that would otherwise be .form or .files + # data. This restores the behavior that was there in Werkzeug + # before 0.9. New code should use :meth:`get_data` explicitly as + # this will make behavior explicit. + return self.get_data(parse_form_data=True) + + def get_data(self, cache=True, as_text=False, parse_form_data=False): + """This reads the buffered incoming data from the client into one + bytestring. By default this is cached but that behavior can be + changed by setting `cache` to `False`. + + Usually it's a bad idea to call this method without checking the + content length first as a client could send dozens of megabytes or more + to cause memory problems on the server. + + Note that if the form data was already parsed this method will not + return anything as form data parsing does not cache the data like + this method does. To implicitly invoke form data parsing function + set `parse_form_data` to `True`. When this is done the return value + of this method will be an empty string if the form parser handles + the data. This generally is not necessary as if the whole data is + cached (which is the default) the form parser will used the cached + data to parse the form data. Please be generally aware of checking + the content length first in any case before calling this method + to avoid exhausting server memory. + + If `as_text` is set to `True` the return value will be a decoded + unicode string. + + .. versionadded:: 0.9 + """ + rv = getattr(self, '_cached_data', None) + if rv is None: + if parse_form_data: + self._load_form_data() + rv = self.stream.read() + if cache: + self._cached_data = rv + if as_text: + rv = rv.decode(self.charset, self.encoding_errors) + return rv + + @cached_property + def form(self): + """The form parameters. By default an + :class:`~werkzeug.datastructures.ImmutableMultiDict` + is returned from this function. This can be changed by setting + :attr:`parameter_storage_class` to a different type. This might + be necessary if the order of the form data is important. + + Please keep in mind that file uploads will not end up here, but instead + in the :attr:`files` attribute. + + .. versionchanged:: 0.9 + + Previous to Werkzeug 0.9 this would only contain form data for POST + and PUT requests. + """ + self._load_form_data() + return self.form + + @cached_property + def values(self): + """A :class:`werkzeug.datastructures.CombinedMultiDict` that combines + :attr:`args` and :attr:`form`.""" + args = [] + for d in self.args, self.form: + if not isinstance(d, MultiDict): + d = MultiDict(d) + args.append(d) + return CombinedMultiDict(args) + + @cached_property + def files(self): + """:class:`~werkzeug.datastructures.MultiDict` object containing + all uploaded files. Each key in :attr:`files` is the name from the + ````. Each value in :attr:`files` is a + Werkzeug :class:`~werkzeug.datastructures.FileStorage` object. + + It basically behaves like a standard file object you know from Python, + with the difference that it also has a + :meth:`~werkzeug.datastructures.FileStorage.save` function that can + store the file on the filesystem. + + Note that :attr:`files` will only contain data if the request method was + POST, PUT or PATCH and the ``

    `` that posted to the request had + ``enctype="multipart/form-data"``. It will be empty otherwise. + + See the :class:`~werkzeug.datastructures.MultiDict` / + :class:`~werkzeug.datastructures.FileStorage` documentation for + more details about the used data structure. + """ + self._load_form_data() + return self.files + + @cached_property + def cookies(self): + """A :class:`dict` with the contents of all cookies transmitted with + the request.""" + return parse_cookie(self.environ, self.charset, + self.encoding_errors, + cls=self.dict_storage_class) + + @cached_property + def headers(self): + """The headers from the WSGI environ as immutable + :class:`~werkzeug.datastructures.EnvironHeaders`. + """ + return EnvironHeaders(self.environ) + + @cached_property + def path(self): + """Requested path as unicode. This works a bit like the regular path + info in the WSGI environment but will always include a leading slash, + even if the URL root is accessed. + """ + raw_path = wsgi_decoding_dance(self.environ.get('PATH_INFO') or '', + self.charset, self.encoding_errors) + return '/' + raw_path.lstrip('/') + + @cached_property + def full_path(self): + """Requested path as unicode, including the query string.""" + return self.path + u'?' + to_unicode(self.query_string, self.url_charset) + + @cached_property + def script_root(self): + """The root path of the script without the trailing slash.""" + raw_path = wsgi_decoding_dance(self.environ.get('SCRIPT_NAME') or '', + self.charset, self.encoding_errors) + return raw_path.rstrip('/') + + @cached_property + def url(self): + """The reconstructed current URL as IRI. + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, + trusted_hosts=self.trusted_hosts) + + @cached_property + def base_url(self): + """Like :attr:`url` but without the querystring + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, strip_querystring=True, + trusted_hosts=self.trusted_hosts) + + @cached_property + def url_root(self): + """The full URL root (with hostname), this is the application + root as IRI. + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, True, + trusted_hosts=self.trusted_hosts) + + @cached_property + def host_url(self): + """Just the host with scheme as IRI. + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, host_only=True, + trusted_hosts=self.trusted_hosts) + + @cached_property + def host(self): + """Just the host including the port if available. + See also: :attr:`trusted_hosts`. + """ + return get_host(self.environ, trusted_hosts=self.trusted_hosts) + + query_string = environ_property( + 'QUERY_STRING', '', read_only=True, + load_func=wsgi_get_bytes, doc='The URL parameters as raw bytestring.') + method = environ_property( + 'REQUEST_METHOD', 'GET', read_only=True, + load_func=lambda x: x.upper(), + doc="The request method. (For example ``'GET'`` or ``'POST'``).") + + @cached_property + def access_route(self): + """If a forwarded header exists this is a list of all ip addresses + from the client ip to the last proxy server. + """ + if 'HTTP_X_FORWARDED_FOR' in self.environ: + addr = self.environ['HTTP_X_FORWARDED_FOR'].split(',') + return self.list_storage_class([x.strip() for x in addr]) + elif 'REMOTE_ADDR' in self.environ: + return self.list_storage_class([self.environ['REMOTE_ADDR']]) + return self.list_storage_class() + + @property + def remote_addr(self): + """The remote address of the client.""" + return self.environ.get('REMOTE_ADDR') + + remote_user = environ_property('REMOTE_USER', doc=''' + If the server supports user authentication, and the script is + protected, this attribute contains the username the user has + authenticated as.''') + + scheme = environ_property('wsgi.url_scheme', doc=''' + URL scheme (http or https). + + .. versionadded:: 0.7''') + + @property + def is_xhr(self): + """True if the request was triggered via a JavaScript XMLHttpRequest. + This only works with libraries that support the ``X-Requested-With`` + header and set it to "XMLHttpRequest". Libraries that do that are + prototype, jQuery and Mochikit and probably some more. + + .. deprecated:: 0.13 + ``X-Requested-With`` is not standard and is unreliable. + """ + warn(DeprecationWarning( + 'Request.is_xhr is deprecated. Given that the X-Requested-With ' + 'header is not a part of any spec, it is not reliable' + ), stacklevel=2) + return self.environ.get( + 'HTTP_X_REQUESTED_WITH', '' + ).lower() == 'xmlhttprequest' + + is_secure = property(lambda x: x.environ['wsgi.url_scheme'] == 'https', + doc='`True` if the request is secure.') + is_multithread = environ_property('wsgi.multithread', doc=''' + boolean that is `True` if the application is served by + a multithreaded WSGI server.''') + is_multiprocess = environ_property('wsgi.multiprocess', doc=''' + boolean that is `True` if the application is served by + a WSGI server that spawns multiple processes.''') + is_run_once = environ_property('wsgi.run_once', doc=''' + boolean that is `True` if the application will be executed only + once in a process lifetime. This is the case for CGI for example, + but it's not guaranteed that the execution only happens one time.''') + + +class BaseResponse(object): + + """Base response class. The most important fact about a response object + is that it's a regular WSGI application. It's initialized with a couple + of response parameters (headers, body, status code etc.) and will start a + valid WSGI response when called with the environ and start response + callable. + + Because it's a WSGI application itself processing usually ends before the + actual response is sent to the server. This helps debugging systems + because they can catch all the exceptions before responses are started. + + Here a small example WSGI application that takes advantage of the + response objects:: + + from werkzeug.wrappers import BaseResponse as Response + + def index(): + return Response('Index page') + + def application(environ, start_response): + path = environ.get('PATH_INFO') or '/' + if path == '/': + response = index() + else: + response = Response('Not Found', status=404) + return response(environ, start_response) + + Like :class:`BaseRequest` which object is lacking a lot of functionality + implemented in mixins. This gives you a better control about the actual + API of your response objects, so you can create subclasses and add custom + functionality. A full featured response object is available as + :class:`Response` which implements a couple of useful mixins. + + To enforce a new type of already existing responses you can use the + :meth:`force_type` method. This is useful if you're working with different + subclasses of response objects and you want to post process them with a + known interface. + + Per default the response object will assume all the text data is `utf-8` + encoded. Please refer to `the unicode chapter `_ for more + details about customizing the behavior. + + Response can be any kind of iterable or string. If it's a string it's + considered being an iterable with one item which is the string passed. + Headers can be a list of tuples or a + :class:`~werkzeug.datastructures.Headers` object. + + Special note for `mimetype` and `content_type`: For most mime types + `mimetype` and `content_type` work the same, the difference affects + only 'text' mimetypes. If the mimetype passed with `mimetype` is a + mimetype starting with `text/`, the charset parameter of the response + object is appended to it. In contrast the `content_type` parameter is + always added as header unmodified. + + .. versionchanged:: 0.5 + the `direct_passthrough` parameter was added. + + :param response: a string or response iterable. + :param status: a string with a status or an integer with the status code. + :param headers: a list of headers or a + :class:`~werkzeug.datastructures.Headers` object. + :param mimetype: the mimetype for the response. See notice above. + :param content_type: the content type for the response. See notice above. + :param direct_passthrough: if set to `True` :meth:`iter_encoded` is not + called before iteration which makes it + possible to pass special iterators through + unchanged (see :func:`wrap_file` for more + details.) + """ + + #: the charset of the response. + charset = 'utf-8' + + #: the default status if none is provided. + default_status = 200 + + #: the default mimetype if none is provided. + default_mimetype = 'text/plain' + + #: if set to `False` accessing properties on the response object will + #: not try to consume the response iterator and convert it into a list. + #: + #: .. versionadded:: 0.6.2 + #: + #: That attribute was previously called `implicit_seqence_conversion`. + #: (Notice the typo). If you did use this feature, you have to adapt + #: your code to the name change. + implicit_sequence_conversion = True + + #: Should this response object correct the location header to be RFC + #: conformant? This is true by default. + #: + #: .. versionadded:: 0.8 + autocorrect_location_header = True + + #: Should this response object automatically set the content-length + #: header if possible? This is true by default. + #: + #: .. versionadded:: 0.8 + automatically_set_content_length = True + + #: Warn if a cookie header exceeds this size. The default, 4093, should be + #: safely `supported by most browsers `_. A cookie larger than + #: this size will still be sent, but it may be ignored or handled + #: incorrectly by some browsers. Set to 0 to disable this check. + #: + #: .. versionadded:: 0.13 + #: + #: .. _`cookie`: http://browsercookielimits.squawky.net/ + max_cookie_size = 4093 + + def __init__(self, response=None, status=None, headers=None, + mimetype=None, content_type=None, direct_passthrough=False): + if isinstance(headers, Headers): + self.headers = headers + elif not headers: + self.headers = Headers() + else: + self.headers = Headers(headers) + + if content_type is None: + if mimetype is None and 'content-type' not in self.headers: + mimetype = self.default_mimetype + if mimetype is not None: + mimetype = get_content_type(mimetype, self.charset) + content_type = mimetype + if content_type is not None: + self.headers['Content-Type'] = content_type + if status is None: + status = self.default_status + if isinstance(status, integer_types): + self.status_code = status + else: + self.status = status + + self.direct_passthrough = direct_passthrough + self._on_close = [] + + # we set the response after the headers so that if a class changes + # the charset attribute, the data is set in the correct charset. + if response is None: + self.response = [] + elif isinstance(response, (text_type, bytes, bytearray)): + self.set_data(response) + else: + self.response = response + + def call_on_close(self, func): + """Adds a function to the internal list of functions that should + be called as part of closing down the response. Since 0.7 this + function also returns the function that was passed so that this + can be used as a decorator. + + .. versionadded:: 0.6 + """ + self._on_close.append(func) + return func + + def __repr__(self): + if self.is_sequence: + body_info = '%d bytes' % sum(map(len, self.iter_encoded())) + else: + body_info = 'streamed' if self.is_streamed else 'likely-streamed' + return '<%s %s [%s]>' % ( + self.__class__.__name__, + body_info, + self.status + ) + + @classmethod + def force_type(cls, response, environ=None): + """Enforce that the WSGI response is a response object of the current + type. Werkzeug will use the :class:`BaseResponse` internally in many + situations like the exceptions. If you call :meth:`get_response` on an + exception you will get back a regular :class:`BaseResponse` object, even + if you are using a custom subclass. + + This method can enforce a given response type, and it will also + convert arbitrary WSGI callables into response objects if an environ + is provided:: + + # convert a Werkzeug response object into an instance of the + # MyResponseClass subclass. + response = MyResponseClass.force_type(response) + + # convert any WSGI application into a response object + response = MyResponseClass.force_type(response, environ) + + This is especially useful if you want to post-process responses in + the main dispatcher and use functionality provided by your subclass. + + Keep in mind that this will modify response objects in place if + possible! + + :param response: a response object or wsgi application. + :param environ: a WSGI environment object. + :return: a response object. + """ + if not isinstance(response, BaseResponse): + if environ is None: + raise TypeError('cannot convert WSGI application into ' + 'response objects without an environ') + response = BaseResponse(*_run_wsgi_app(response, environ)) + response.__class__ = cls + return response + + @classmethod + def from_app(cls, app, environ, buffered=False): + """Create a new response object from an application output. This + works best if you pass it an application that returns a generator all + the time. Sometimes applications may use the `write()` callable + returned by the `start_response` function. This tries to resolve such + edge cases automatically. But if you don't get the expected output + you should set `buffered` to `True` which enforces buffering. + + :param app: the WSGI application to execute. + :param environ: the WSGI environment to execute against. + :param buffered: set to `True` to enforce buffering. + :return: a response object. + """ + return cls(*_run_wsgi_app(app, environ, buffered)) + + def _get_status_code(self): + return self._status_code + + def _set_status_code(self, code): + self._status_code = code + try: + self._status = '%d %s' % (code, HTTP_STATUS_CODES[code].upper()) + except KeyError: + self._status = '%d UNKNOWN' % code + status_code = property(_get_status_code, _set_status_code, + doc='The HTTP Status code as number') + del _get_status_code, _set_status_code + + def _get_status(self): + return self._status + + def _set_status(self, value): + try: + self._status = to_native(value) + except AttributeError: + raise TypeError('Invalid status argument') + + try: + self._status_code = int(self._status.split(None, 1)[0]) + except ValueError: + self._status_code = 0 + self._status = '0 %s' % self._status + except IndexError: + raise ValueError('Empty status argument') + status = property(_get_status, _set_status, doc='The HTTP Status code') + del _get_status, _set_status + + def get_data(self, as_text=False): + """The string representation of the request body. Whenever you call + this property the request iterable is encoded and flattened. This + can lead to unwanted behavior if you stream big data. + + This behavior can be disabled by setting + :attr:`implicit_sequence_conversion` to `False`. + + If `as_text` is set to `True` the return value will be a decoded + unicode string. + + .. versionadded:: 0.9 + """ + self._ensure_sequence() + rv = b''.join(self.iter_encoded()) + if as_text: + rv = rv.decode(self.charset) + return rv + + def set_data(self, value): + """Sets a new string as response. The value set must either by a + unicode or bytestring. If a unicode string is set it's encoded + automatically to the charset of the response (utf-8 by default). + + .. versionadded:: 0.9 + """ + # if an unicode string is set, it's encoded directly so that we + # can set the content length + if isinstance(value, text_type): + value = value.encode(self.charset) + else: + value = bytes(value) + self.response = [value] + if self.automatically_set_content_length: + self.headers['Content-Length'] = str(len(value)) + + data = property(get_data, set_data, doc=''' + A descriptor that calls :meth:`get_data` and :meth:`set_data`. This + should not be used and will eventually get deprecated. + ''') + + def calculate_content_length(self): + """Returns the content length if available or `None` otherwise.""" + try: + self._ensure_sequence() + except RuntimeError: + return None + return sum(len(x) for x in self.iter_encoded()) + + def _ensure_sequence(self, mutable=False): + """This method can be called by methods that need a sequence. If + `mutable` is true, it will also ensure that the response sequence + is a standard Python list. + + .. versionadded:: 0.6 + """ + if self.is_sequence: + # if we need a mutable object, we ensure it's a list. + if mutable and not isinstance(self.response, list): + self.response = list(self.response) + return + if self.direct_passthrough: + raise RuntimeError('Attempted implicit sequence conversion ' + 'but the response object is in direct ' + 'passthrough mode.') + if not self.implicit_sequence_conversion: + raise RuntimeError('The response object required the iterable ' + 'to be a sequence, but the implicit ' + 'conversion was disabled. Call ' + 'make_sequence() yourself.') + self.make_sequence() + + def make_sequence(self): + """Converts the response iterator in a list. By default this happens + automatically if required. If `implicit_sequence_conversion` is + disabled, this method is not automatically called and some properties + might raise exceptions. This also encodes all the items. + + .. versionadded:: 0.6 + """ + if not self.is_sequence: + # if we consume an iterable we have to ensure that the close + # method of the iterable is called if available when we tear + # down the response + close = getattr(self.response, 'close', None) + self.response = list(self.iter_encoded()) + if close is not None: + self.call_on_close(close) + + def iter_encoded(self): + """Iter the response encoded with the encoding of the response. + If the response object is invoked as WSGI application the return + value of this method is used as application iterator unless + :attr:`direct_passthrough` was activated. + """ + if __debug__: + _warn_if_string(self.response) + # Encode in a separate function so that self.response is fetched + # early. This allows us to wrap the response with the return + # value from get_app_iter or iter_encoded. + return _iter_encoded(self.response, self.charset) + + def set_cookie(self, key, value='', max_age=None, expires=None, + path='/', domain=None, secure=False, httponly=False, + samesite=None): + """Sets a cookie. The parameters are the same as in the cookie `Morsel` + object in the Python standard library but it accepts unicode data, too. + + A warning is raised if the size of the cookie header exceeds + :attr:`max_cookie_size`, but the header will still be set. + + :param key: the key (name) of the cookie to be set. + :param value: the value of the cookie. + :param max_age: should be a number of seconds, or `None` (default) if + the cookie should last only as long as the client's + browser session. + :param expires: should be a `datetime` object or UNIX timestamp. + :param path: limits the cookie to a given path, per default it will + span the whole domain. + :param domain: if you want to set a cross-domain cookie. For example, + ``domain=".example.com"`` will set a cookie that is + readable by the domain ``www.example.com``, + ``foo.example.com`` etc. Otherwise, a cookie will only + be readable by the domain that set it. + :param secure: If `True`, the cookie will only be available via HTTPS + :param httponly: disallow JavaScript to access the cookie. This is an + extension to the cookie standard and probably not + supported by all browsers. + :param samesite: Limits the scope of the cookie such that it will only + be attached to requests if those requests are + "same-site". + """ + self.headers.add('Set-Cookie', dump_cookie( + key, + value=value, + max_age=max_age, + expires=expires, + path=path, + domain=domain, + secure=secure, + httponly=httponly, + charset=self.charset, + max_size=self.max_cookie_size, + samesite=samesite + )) + + def delete_cookie(self, key, path='/', domain=None): + """Delete a cookie. Fails silently if key doesn't exist. + + :param key: the key (name) of the cookie to be deleted. + :param path: if the cookie that should be deleted was limited to a + path, the path has to be defined here. + :param domain: if the cookie that should be deleted was limited to a + domain, that domain has to be defined here. + """ + self.set_cookie(key, expires=0, max_age=0, path=path, domain=domain) + + @property + def is_streamed(self): + """If the response is streamed (the response is not an iterable with + a length information) this property is `True`. In this case streamed + means that there is no information about the number of iterations. + This is usually `True` if a generator is passed to the response object. + + This is useful for checking before applying some sort of post + filtering that should not take place for streamed responses. + """ + try: + len(self.response) + except (TypeError, AttributeError): + return True + return False + + @property + def is_sequence(self): + """If the iterator is buffered, this property will be `True`. A + response object will consider an iterator to be buffered if the + response attribute is a list or tuple. + + .. versionadded:: 0.6 + """ + return isinstance(self.response, (tuple, list)) + + def close(self): + """Close the wrapped response if possible. You can also use the object + in a with statement which will automatically close it. + + .. versionadded:: 0.9 + Can now be used in a with statement. + """ + if hasattr(self.response, 'close'): + self.response.close() + for func in self._on_close: + func() + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close() + + def freeze(self): + """Call this method if you want to make your response object ready for + being pickled. This buffers the generator if there is one. It will + also set the `Content-Length` header to the length of the body. + + .. versionchanged:: 0.6 + The `Content-Length` header is now set. + """ + # we explicitly set the length to a list of the *encoded* response + # iterator. Even if the implicit sequence conversion is disabled. + self.response = list(self.iter_encoded()) + self.headers['Content-Length'] = str(sum(map(len, self.response))) + + def get_wsgi_headers(self, environ): + """This is automatically called right before the response is started + and returns headers modified for the given environment. It returns a + copy of the headers from the response with some modifications applied + if necessary. + + For example the location header (if present) is joined with the root + URL of the environment. Also the content length is automatically set + to zero here for certain status codes. + + .. versionchanged:: 0.6 + Previously that function was called `fix_headers` and modified + the response object in place. Also since 0.6, IRIs in location + and content-location headers are handled properly. + + Also starting with 0.6, Werkzeug will attempt to set the content + length if it is able to figure it out on its own. This is the + case if all the strings in the response iterable are already + encoded and the iterable is buffered. + + :param environ: the WSGI environment of the request. + :return: returns a new :class:`~werkzeug.datastructures.Headers` + object. + """ + headers = Headers(self.headers) + location = None + content_location = None + content_length = None + status = self.status_code + + # iterate over the headers to find all values in one go. Because + # get_wsgi_headers is used each response that gives us a tiny + # speedup. + for key, value in headers: + ikey = key.lower() + if ikey == u'location': + location = value + elif ikey == u'content-location': + content_location = value + elif ikey == u'content-length': + content_length = value + + # make sure the location header is an absolute URL + if location is not None: + old_location = location + if isinstance(location, text_type): + # Safe conversion is necessary here as we might redirect + # to a broken URI scheme (for instance itms-services). + location = iri_to_uri(location, safe_conversion=True) + + if self.autocorrect_location_header: + current_url = get_current_url(environ, root_only=True) + if isinstance(current_url, text_type): + current_url = iri_to_uri(current_url) + location = url_join(current_url, location) + if location != old_location: + headers['Location'] = location + + # make sure the content location is a URL + if content_location is not None and \ + isinstance(content_location, text_type): + headers['Content-Location'] = iri_to_uri(content_location) + + if status in (304, 412): + remove_entity_headers(headers) + + # if we can determine the content length automatically, we + # should try to do that. But only if this does not involve + # flattening the iterator or encoding of unicode strings in + # the response. We however should not do that if we have a 304 + # response. + if self.automatically_set_content_length and \ + self.is_sequence and content_length is None and \ + status not in (204, 304) and \ + not (100 <= status < 200): + try: + content_length = sum(len(to_bytes(x, 'ascii')) + for x in self.response) + except UnicodeError: + # aha, something non-bytestringy in there, too bad, we + # can't safely figure out the length of the response. + pass + else: + headers['Content-Length'] = str(content_length) + + return headers + + def get_app_iter(self, environ): + """Returns the application iterator for the given environ. Depending + on the request method and the current status code the return value + might be an empty response rather than the one from the response. + + If the request method is `HEAD` or the status code is in a range + where the HTTP specification requires an empty response, an empty + iterable is returned. + + .. versionadded:: 0.6 + + :param environ: the WSGI environment of the request. + :return: a response iterable. + """ + status = self.status_code + if environ['REQUEST_METHOD'] == 'HEAD' or \ + 100 <= status < 200 or status in (204, 304, 412): + iterable = () + elif self.direct_passthrough: + if __debug__: + _warn_if_string(self.response) + return self.response + else: + iterable = self.iter_encoded() + return ClosingIterator(iterable, self.close) + + def get_wsgi_response(self, environ): + """Returns the final WSGI response as tuple. The first item in + the tuple is the application iterator, the second the status and + the third the list of headers. The response returned is created + specially for the given environment. For example if the request + method in the WSGI environment is ``'HEAD'`` the response will + be empty and only the headers and status code will be present. + + .. versionadded:: 0.6 + + :param environ: the WSGI environment of the request. + :return: an ``(app_iter, status, headers)`` tuple. + """ + headers = self.get_wsgi_headers(environ) + app_iter = self.get_app_iter(environ) + return app_iter, self.status, headers.to_wsgi_list() + + def __call__(self, environ, start_response): + """Process this response as WSGI application. + + :param environ: the WSGI environment. + :param start_response: the response callable provided by the WSGI + server. + :return: an application iterator + """ + app_iter, status, headers = self.get_wsgi_response(environ) + start_response(status, headers) + return app_iter + + +class AcceptMixin(object): + + """A mixin for classes with an :attr:`~BaseResponse.environ` attribute + to get all the HTTP accept headers as + :class:`~werkzeug.datastructures.Accept` objects (or subclasses + thereof). + """ + + @cached_property + def accept_mimetypes(self): + """List of mimetypes this client supports as + :class:`~werkzeug.datastructures.MIMEAccept` object. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT'), MIMEAccept) + + @cached_property + def accept_charsets(self): + """List of charsets this client supports as + :class:`~werkzeug.datastructures.CharsetAccept` object. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT_CHARSET'), + CharsetAccept) + + @cached_property + def accept_encodings(self): + """List of encodings this client accepts. Encodings in a HTTP term + are compression encodings such as gzip. For charsets have a look at + :attr:`accept_charset`. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT_ENCODING')) + + @cached_property + def accept_languages(self): + """List of languages this client accepts as + :class:`~werkzeug.datastructures.LanguageAccept` object. + + .. versionchanged 0.5 + In previous versions this was a regular + :class:`~werkzeug.datastructures.Accept` object. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT_LANGUAGE'), + LanguageAccept) + + +class ETagRequestMixin(object): + + """Add entity tag and cache descriptors to a request object or object with + a WSGI environment available as :attr:`~BaseRequest.environ`. This not + only provides access to etags but also to the cache control header. + """ + + @cached_property + def cache_control(self): + """A :class:`~werkzeug.datastructures.RequestCacheControl` object + for the incoming cache control headers. + """ + cache_control = self.environ.get('HTTP_CACHE_CONTROL') + return parse_cache_control_header(cache_control, None, + RequestCacheControl) + + @cached_property + def if_match(self): + """An object containing all the etags in the `If-Match` header. + + :rtype: :class:`~werkzeug.datastructures.ETags` + """ + return parse_etags(self.environ.get('HTTP_IF_MATCH')) + + @cached_property + def if_none_match(self): + """An object containing all the etags in the `If-None-Match` header. + + :rtype: :class:`~werkzeug.datastructures.ETags` + """ + return parse_etags(self.environ.get('HTTP_IF_NONE_MATCH')) + + @cached_property + def if_modified_since(self): + """The parsed `If-Modified-Since` header as datetime object.""" + return parse_date(self.environ.get('HTTP_IF_MODIFIED_SINCE')) + + @cached_property + def if_unmodified_since(self): + """The parsed `If-Unmodified-Since` header as datetime object.""" + return parse_date(self.environ.get('HTTP_IF_UNMODIFIED_SINCE')) + + @cached_property + def if_range(self): + """The parsed `If-Range` header. + + .. versionadded:: 0.7 + + :rtype: :class:`~werkzeug.datastructures.IfRange` + """ + return parse_if_range_header(self.environ.get('HTTP_IF_RANGE')) + + @cached_property + def range(self): + """The parsed `Range` header. + + .. versionadded:: 0.7 + + :rtype: :class:`~werkzeug.datastructures.Range` + """ + return parse_range_header(self.environ.get('HTTP_RANGE')) + + +class UserAgentMixin(object): + + """Adds a `user_agent` attribute to the request object which contains the + parsed user agent of the browser that triggered the request as a + :class:`~werkzeug.useragents.UserAgent` object. + """ + + @cached_property + def user_agent(self): + """The current user agent.""" + from werkzeug.useragents import UserAgent + return UserAgent(self.environ) + + +class AuthorizationMixin(object): + + """Adds an :attr:`authorization` property that represents the parsed + value of the `Authorization` header as + :class:`~werkzeug.datastructures.Authorization` object. + """ + + @cached_property + def authorization(self): + """The `Authorization` object in parsed form.""" + header = self.environ.get('HTTP_AUTHORIZATION') + return parse_authorization_header(header) + + +class StreamOnlyMixin(object): + + """If mixed in before the request object this will change the bahavior + of it to disable handling of form parsing. This disables the + :attr:`files`, :attr:`form` attributes and will just provide a + :attr:`stream` attribute that however is always available. + + .. versionadded:: 0.9 + """ + + disable_data_descriptor = True + want_form_data_parsed = False + + +class ETagResponseMixin(object): + + """Adds extra functionality to a response object for etag and cache + handling. This mixin requires an object with at least a `headers` + object that implements a dict like interface similar to + :class:`~werkzeug.datastructures.Headers`. + + If you want the :meth:`freeze` method to automatically add an etag, you + have to mixin this method before the response base class. The default + response class does not do that. + """ + + @property + def cache_control(self): + """The Cache-Control general-header field is used to specify + directives that MUST be obeyed by all caching mechanisms along the + request/response chain. + """ + def on_update(cache_control): + if not cache_control and 'cache-control' in self.headers: + del self.headers['cache-control'] + elif cache_control: + self.headers['Cache-Control'] = cache_control.to_header() + return parse_cache_control_header(self.headers.get('cache-control'), + on_update, + ResponseCacheControl) + + def _wrap_response(self, start, length): + """Wrap existing Response in case of Range Request context.""" + if self.status_code == 206: + self.response = _RangeWrapper(self.response, start, length) + + def _is_range_request_processable(self, environ): + """Return ``True`` if `Range` header is present and if underlying + resource is considered unchanged when compared with `If-Range` header. + """ + return ( + 'HTTP_IF_RANGE' not in environ + or not is_resource_modified( + environ, self.headers.get('etag'), None, + self.headers.get('last-modified'), ignore_if_range=False + ) + ) and 'HTTP_RANGE' in environ + + def _process_range_request(self, environ, complete_length=None, accept_ranges=None): + """Handle Range Request related headers (RFC7233). If `Accept-Ranges` + header is valid, and Range Request is processable, we set the headers + as described by the RFC, and wrap the underlying response in a + RangeWrapper. + + Returns ``True`` if Range Request can be fulfilled, ``False`` otherwise. + + :raises: :class:`~werkzeug.exceptions.RequestedRangeNotSatisfiable` + if `Range` header could not be parsed or satisfied. + """ + from werkzeug.exceptions import RequestedRangeNotSatisfiable + if accept_ranges is None: + return False + self.headers['Accept-Ranges'] = accept_ranges + if not self._is_range_request_processable(environ) or complete_length is None: + return False + parsed_range = parse_range_header(environ.get('HTTP_RANGE')) + if parsed_range is None: + raise RequestedRangeNotSatisfiable(complete_length) + range_tuple = parsed_range.range_for_length(complete_length) + content_range_header = parsed_range.to_content_range_header(complete_length) + if range_tuple is None or content_range_header is None: + raise RequestedRangeNotSatisfiable(complete_length) + content_length = range_tuple[1] - range_tuple[0] + # Be sure not to send 206 response + # if requested range is the full content. + if content_length != complete_length: + self.headers['Content-Length'] = content_length + self.content_range = content_range_header + self.status_code = 206 + self._wrap_response(range_tuple[0], content_length) + return True + return False + + def make_conditional(self, request_or_environ, accept_ranges=False, + complete_length=None): + """Make the response conditional to the request. This method works + best if an etag was defined for the response already. The `add_etag` + method can be used to do that. If called without etag just the date + header is set. + + This does nothing if the request method in the request or environ is + anything but GET or HEAD. + + For optimal performance when handling range requests, it's recommended + that your response data object implements `seekable`, `seek` and `tell` + methods as described by :py:class:`io.IOBase`. Objects returned by + :meth:`~werkzeug.wsgi.wrap_file` automatically implement those methods. + + It does not remove the body of the response because that's something + the :meth:`__call__` function does for us automatically. + + Returns self so that you can do ``return resp.make_conditional(req)`` + but modifies the object in-place. + + :param request_or_environ: a request object or WSGI environment to be + used to make the response conditional + against. + :param accept_ranges: This parameter dictates the value of + `Accept-Ranges` header. If ``False`` (default), + the header is not set. If ``True``, it will be set + to ``"bytes"``. If ``None``, it will be set to + ``"none"``. If it's a string, it will use this + value. + :param complete_length: Will be used only in valid Range Requests. + It will set `Content-Range` complete length + value and compute `Content-Length` real value. + This parameter is mandatory for successful + Range Requests completion. + :raises: :class:`~werkzeug.exceptions.RequestedRangeNotSatisfiable` + if `Range` header could not be parsed or satisfied. + """ + environ = _get_environ(request_or_environ) + if environ['REQUEST_METHOD'] in ('GET', 'HEAD'): + # if the date is not in the headers, add it now. We however + # will not override an already existing header. Unfortunately + # this header will be overriden by many WSGI servers including + # wsgiref. + if 'date' not in self.headers: + self.headers['Date'] = http_date() + accept_ranges = _clean_accept_ranges(accept_ranges) + is206 = self._process_range_request(environ, complete_length, accept_ranges) + if not is206 and not is_resource_modified( + environ, self.headers.get('etag'), None, + self.headers.get('last-modified') + ): + if parse_etags(environ.get('HTTP_IF_MATCH')): + self.status_code = 412 + else: + self.status_code = 304 + if self.automatically_set_content_length and 'content-length' not in self.headers: + length = self.calculate_content_length() + if length is not None: + self.headers['Content-Length'] = length + return self + + def add_etag(self, overwrite=False, weak=False): + """Add an etag for the current response if there is none yet.""" + if overwrite or 'etag' not in self.headers: + self.set_etag(generate_etag(self.get_data()), weak) + + def set_etag(self, etag, weak=False): + """Set the etag, and override the old one if there was one.""" + self.headers['ETag'] = quote_etag(etag, weak) + + def get_etag(self): + """Return a tuple in the form ``(etag, is_weak)``. If there is no + ETag the return value is ``(None, None)``. + """ + return unquote_etag(self.headers.get('ETag')) + + def freeze(self, no_etag=False): + """Call this method if you want to make your response object ready for + pickeling. This buffers the generator if there is one. This also + sets the etag unless `no_etag` is set to `True`. + """ + if not no_etag: + self.add_etag() + super(ETagResponseMixin, self).freeze() + + accept_ranges = header_property('Accept-Ranges', doc=''' + The `Accept-Ranges` header. Even though the name would indicate + that multiple values are supported, it must be one string token only. + + The values ``'bytes'`` and ``'none'`` are common. + + .. versionadded:: 0.7''') + + def _get_content_range(self): + def on_update(rng): + if not rng: + del self.headers['content-range'] + else: + self.headers['Content-Range'] = rng.to_header() + rv = parse_content_range_header(self.headers.get('content-range'), + on_update) + # always provide a content range object to make the descriptor + # more user friendly. It provides an unset() method that can be + # used to remove the header quickly. + if rv is None: + rv = ContentRange(None, None, None, on_update=on_update) + return rv + + def _set_content_range(self, value): + if not value: + del self.headers['content-range'] + elif isinstance(value, string_types): + self.headers['Content-Range'] = value + else: + self.headers['Content-Range'] = value.to_header() + content_range = property(_get_content_range, _set_content_range, doc=''' + The `Content-Range` header as + :class:`~werkzeug.datastructures.ContentRange` object. Even if the + header is not set it wil provide such an object for easier + manipulation. + + .. versionadded:: 0.7''') + del _get_content_range, _set_content_range + + +class ResponseStream(object): + + """A file descriptor like object used by the :class:`ResponseStreamMixin` to + represent the body of the stream. It directly pushes into the response + iterable of the response object. + """ + + mode = 'wb+' + + def __init__(self, response): + self.response = response + self.closed = False + + def write(self, value): + if self.closed: + raise ValueError('I/O operation on closed file') + self.response._ensure_sequence(mutable=True) + self.response.response.append(value) + self.response.headers.pop('Content-Length', None) + return len(value) + + def writelines(self, seq): + for item in seq: + self.write(item) + + def close(self): + self.closed = True + + def flush(self): + if self.closed: + raise ValueError('I/O operation on closed file') + + def isatty(self): + if self.closed: + raise ValueError('I/O operation on closed file') + return False + + def tell(self): + self.response._ensure_sequence() + return sum(map(len, self.response.response)) + + @property + def encoding(self): + return self.response.charset + + +class ResponseStreamMixin(object): + + """Mixin for :class:`BaseRequest` subclasses. Classes that inherit from + this mixin will automatically get a :attr:`stream` property that provides + a write-only interface to the response iterable. + """ + + @cached_property + def stream(self): + """The response iterable as write-only stream.""" + return ResponseStream(self) + + +class CommonRequestDescriptorsMixin(object): + + """A mixin for :class:`BaseRequest` subclasses. Request objects that + mix this class in will automatically get descriptors for a couple of + HTTP headers with automatic type conversion. + + .. versionadded:: 0.5 + """ + + content_type = environ_property('CONTENT_TYPE', doc=''' + The Content-Type entity-header field indicates the media type of + the entity-body sent to the recipient or, in the case of the HEAD + method, the media type that would have been sent had the request + been a GET.''') + + @cached_property + def content_length(self): + """The Content-Length entity-header field indicates the size of the + entity-body in bytes or, in the case of the HEAD method, the size of + the entity-body that would have been sent had the request been a + GET. + """ + return get_content_length(self.environ) + + content_encoding = environ_property('HTTP_CONTENT_ENCODING', doc=''' + The Content-Encoding entity-header field is used as a modifier to the + media-type. When present, its value indicates what additional content + codings have been applied to the entity-body, and thus what decoding + mechanisms must be applied in order to obtain the media-type + referenced by the Content-Type header field. + + .. versionadded:: 0.9''') + content_md5 = environ_property('HTTP_CONTENT_MD5', doc=''' + The Content-MD5 entity-header field, as defined in RFC 1864, is an + MD5 digest of the entity-body for the purpose of providing an + end-to-end message integrity check (MIC) of the entity-body. (Note: + a MIC is good for detecting accidental modification of the + entity-body in transit, but is not proof against malicious attacks.) + + .. versionadded:: 0.9''') + referrer = environ_property('HTTP_REFERER', doc=''' + The Referer[sic] request-header field allows the client to specify, + for the server's benefit, the address (URI) of the resource from which + the Request-URI was obtained (the "referrer", although the header + field is misspelled).''') + date = environ_property('HTTP_DATE', None, parse_date, doc=''' + The Date general-header field represents the date and time at which + the message was originated, having the same semantics as orig-date + in RFC 822.''') + max_forwards = environ_property('HTTP_MAX_FORWARDS', None, int, doc=''' + The Max-Forwards request-header field provides a mechanism with the + TRACE and OPTIONS methods to limit the number of proxies or gateways + that can forward the request to the next inbound server.''') + + def _parse_content_type(self): + if not hasattr(self, '_parsed_content_type'): + self._parsed_content_type = \ + parse_options_header(self.environ.get('CONTENT_TYPE', '')) + + @property + def mimetype(self): + """Like :attr:`content_type`, but without parameters (eg, without + charset, type etc.) and always lowercase. For example if the content + type is ``text/HTML; charset=utf-8`` the mimetype would be + ``'text/html'``. + """ + self._parse_content_type() + return self._parsed_content_type[0].lower() + + @property + def mimetype_params(self): + """The mimetype parameters as dict. For example if the content + type is ``text/html; charset=utf-8`` the params would be + ``{'charset': 'utf-8'}``. + """ + self._parse_content_type() + return self._parsed_content_type[1] + + @cached_property + def pragma(self): + """The Pragma general-header field is used to include + implementation-specific directives that might apply to any recipient + along the request/response chain. All pragma directives specify + optional behavior from the viewpoint of the protocol; however, some + systems MAY require that behavior be consistent with the directives. + """ + return parse_set_header(self.environ.get('HTTP_PRAGMA', '')) + + +class CommonResponseDescriptorsMixin(object): + + """A mixin for :class:`BaseResponse` subclasses. Response objects that + mix this class in will automatically get descriptors for a couple of + HTTP headers with automatic type conversion. + """ + + def _get_mimetype(self): + ct = self.headers.get('content-type') + if ct: + return ct.split(';')[0].strip() + + def _set_mimetype(self, value): + self.headers['Content-Type'] = get_content_type(value, self.charset) + + def _get_mimetype_params(self): + def on_update(d): + self.headers['Content-Type'] = \ + dump_options_header(self.mimetype, d) + d = parse_options_header(self.headers.get('content-type', ''))[1] + return CallbackDict(d, on_update) + + mimetype = property(_get_mimetype, _set_mimetype, doc=''' + The mimetype (content type without charset etc.)''') + mimetype_params = property(_get_mimetype_params, doc=''' + The mimetype parameters as dict. For example if the content + type is ``text/html; charset=utf-8`` the params would be + ``{'charset': 'utf-8'}``. + + .. versionadded:: 0.5 + ''') + location = header_property('Location', doc=''' + The Location response-header field is used to redirect the recipient + to a location other than the Request-URI for completion of the request + or identification of a new resource.''') + age = header_property('Age', None, parse_age, dump_age, doc=''' + The Age response-header field conveys the sender's estimate of the + amount of time since the response (or its revalidation) was + generated at the origin server. + + Age values are non-negative decimal integers, representing time in + seconds.''') + content_type = header_property('Content-Type', doc=''' + The Content-Type entity-header field indicates the media type of the + entity-body sent to the recipient or, in the case of the HEAD method, + the media type that would have been sent had the request been a GET. + ''') + content_length = header_property('Content-Length', None, int, str, doc=''' + The Content-Length entity-header field indicates the size of the + entity-body, in decimal number of OCTETs, sent to the recipient or, + in the case of the HEAD method, the size of the entity-body that would + have been sent had the request been a GET.''') + content_location = header_property('Content-Location', doc=''' + The Content-Location entity-header field MAY be used to supply the + resource location for the entity enclosed in the message when that + entity is accessible from a location separate from the requested + resource's URI.''') + content_encoding = header_property('Content-Encoding', doc=''' + The Content-Encoding entity-header field is used as a modifier to the + media-type. When present, its value indicates what additional content + codings have been applied to the entity-body, and thus what decoding + mechanisms must be applied in order to obtain the media-type + referenced by the Content-Type header field.''') + content_md5 = header_property('Content-MD5', doc=''' + The Content-MD5 entity-header field, as defined in RFC 1864, is an + MD5 digest of the entity-body for the purpose of providing an + end-to-end message integrity check (MIC) of the entity-body. (Note: + a MIC is good for detecting accidental modification of the + entity-body in transit, but is not proof against malicious attacks.) + ''') + date = header_property('Date', None, parse_date, http_date, doc=''' + The Date general-header field represents the date and time at which + the message was originated, having the same semantics as orig-date + in RFC 822.''') + expires = header_property('Expires', None, parse_date, http_date, doc=''' + The Expires entity-header field gives the date/time after which the + response is considered stale. A stale cache entry may not normally be + returned by a cache.''') + last_modified = header_property('Last-Modified', None, parse_date, + http_date, doc=''' + The Last-Modified entity-header field indicates the date and time at + which the origin server believes the variant was last modified.''') + + def _get_retry_after(self): + value = self.headers.get('retry-after') + if value is None: + return + elif value.isdigit(): + return datetime.utcnow() + timedelta(seconds=int(value)) + return parse_date(value) + + def _set_retry_after(self, value): + if value is None: + if 'retry-after' in self.headers: + del self.headers['retry-after'] + return + elif isinstance(value, datetime): + value = http_date(value) + else: + value = str(value) + self.headers['Retry-After'] = value + + retry_after = property(_get_retry_after, _set_retry_after, doc=''' + The Retry-After response-header field can be used with a 503 (Service + Unavailable) response to indicate how long the service is expected + to be unavailable to the requesting client. + + Time in seconds until expiration or date.''') + + def _set_property(name, doc=None): + def fget(self): + def on_update(header_set): + if not header_set and name in self.headers: + del self.headers[name] + elif header_set: + self.headers[name] = header_set.to_header() + return parse_set_header(self.headers.get(name), on_update) + + def fset(self, value): + if not value: + del self.headers[name] + elif isinstance(value, string_types): + self.headers[name] = value + else: + self.headers[name] = dump_header(value) + return property(fget, fset, doc=doc) + + vary = _set_property('Vary', doc=''' + The Vary field value indicates the set of request-header fields that + fully determines, while the response is fresh, whether a cache is + permitted to use the response to reply to a subsequent request + without revalidation.''') + content_language = _set_property('Content-Language', doc=''' + The Content-Language entity-header field describes the natural + language(s) of the intended audience for the enclosed entity. Note + that this might not be equivalent to all the languages used within + the entity-body.''') + allow = _set_property('Allow', doc=''' + The Allow entity-header field lists the set of methods supported + by the resource identified by the Request-URI. The purpose of this + field is strictly to inform the recipient of valid methods + associated with the resource. An Allow header field MUST be + present in a 405 (Method Not Allowed) response.''') + + del _set_property, _get_mimetype, _set_mimetype, _get_retry_after, \ + _set_retry_after + + +class WWWAuthenticateMixin(object): + + """Adds a :attr:`www_authenticate` property to a response object.""" + + @property + def www_authenticate(self): + """The `WWW-Authenticate` header in a parsed form.""" + def on_update(www_auth): + if not www_auth and 'www-authenticate' in self.headers: + del self.headers['www-authenticate'] + elif www_auth: + self.headers['WWW-Authenticate'] = www_auth.to_header() + header = self.headers.get('www-authenticate') + return parse_www_authenticate_header(header, on_update) + + +class Request(BaseRequest, AcceptMixin, ETagRequestMixin, + UserAgentMixin, AuthorizationMixin, + CommonRequestDescriptorsMixin): + + """Full featured request object implementing the following mixins: + + - :class:`AcceptMixin` for accept header parsing + - :class:`ETagRequestMixin` for etag and cache control handling + - :class:`UserAgentMixin` for user agent introspection + - :class:`AuthorizationMixin` for http auth handling + - :class:`CommonRequestDescriptorsMixin` for common headers + """ + + +class PlainRequest(StreamOnlyMixin, Request): + + """A request object without special form parsing capabilities. + + .. versionadded:: 0.9 + """ + + +class Response(BaseResponse, ETagResponseMixin, ResponseStreamMixin, + CommonResponseDescriptorsMixin, + WWWAuthenticateMixin): + + """Full featured response object implementing the following mixins: + + - :class:`ETagResponseMixin` for etag and cache control handling + - :class:`ResponseStreamMixin` to add support for the `stream` property + - :class:`CommonResponseDescriptorsMixin` for various HTTP descriptors + - :class:`WWWAuthenticateMixin` for HTTP authentication support + """ diff --git a/pyextra/werkzeug/wsgi.py b/pyextra/werkzeug/wsgi.py new file mode 100644 index 00000000000000..c30021a7b6ae51 --- /dev/null +++ b/pyextra/werkzeug/wsgi.py @@ -0,0 +1,1364 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.wsgi + ~~~~~~~~~~~~~ + + This module implements WSGI related helpers. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import io +try: + import httplib +except ImportError: + from http import client as httplib +import mimetypes +import os +import posixpath +import re +import socket +from datetime import datetime +from functools import partial, update_wrapper +from itertools import chain +from time import mktime, time +from zlib import adler32 + +from werkzeug._compat import BytesIO, PY2, implements_iterator, iteritems, \ + make_literal_wrapper, string_types, text_type, to_bytes, to_unicode, \ + try_coerce_native, wsgi_get_bytes +from werkzeug._internal import _empty_stream, _encode_idna +from werkzeug.filesystem import get_filesystem_encoding +from werkzeug.http import http_date, is_resource_modified, \ + is_hop_by_hop_header +from werkzeug.urls import uri_to_iri, url_join, url_parse, url_quote +from werkzeug.datastructures import EnvironHeaders + + +def responder(f): + """Marks a function as responder. Decorate a function with it and it + will automatically call the return value as WSGI application. + + Example:: + + @responder + def application(environ, start_response): + return Response('Hello World!') + """ + return update_wrapper(lambda *a: f(*a)(*a[-2:]), f) + + +def get_current_url(environ, root_only=False, strip_querystring=False, + host_only=False, trusted_hosts=None): + """A handy helper function that recreates the full URL as IRI for the + current request or parts of it. Here's an example: + + >>> from werkzeug.test import create_environ + >>> env = create_environ("/?param=foo", "http://localhost/script") + >>> get_current_url(env) + 'http://localhost/script/?param=foo' + >>> get_current_url(env, root_only=True) + 'http://localhost/script/' + >>> get_current_url(env, host_only=True) + 'http://localhost/' + >>> get_current_url(env, strip_querystring=True) + 'http://localhost/script/' + + This optionally it verifies that the host is in a list of trusted hosts. + If the host is not in there it will raise a + :exc:`~werkzeug.exceptions.SecurityError`. + + Note that the string returned might contain unicode characters as the + representation is an IRI not an URI. If you need an ASCII only + representation you can use the :func:`~werkzeug.urls.iri_to_uri` + function: + + >>> from werkzeug.urls import iri_to_uri + >>> iri_to_uri(get_current_url(env)) + 'http://localhost/script/?param=foo' + + :param environ: the WSGI environment to get the current URL from. + :param root_only: set `True` if you only want the root URL. + :param strip_querystring: set to `True` if you don't want the querystring. + :param host_only: set to `True` if the host URL should be returned. + :param trusted_hosts: a list of trusted hosts, see :func:`host_is_trusted` + for more information. + """ + tmp = [environ['wsgi.url_scheme'], '://', get_host(environ, trusted_hosts)] + cat = tmp.append + if host_only: + return uri_to_iri(''.join(tmp) + '/') + cat(url_quote(wsgi_get_bytes(environ.get('SCRIPT_NAME', ''))).rstrip('/')) + cat('/') + if not root_only: + cat(url_quote(wsgi_get_bytes(environ.get('PATH_INFO', '')).lstrip(b'/'))) + if not strip_querystring: + qs = get_query_string(environ) + if qs: + cat('?' + qs) + return uri_to_iri(''.join(tmp)) + + +def host_is_trusted(hostname, trusted_list): + """Checks if a host is trusted against a list. This also takes care + of port normalization. + + .. versionadded:: 0.9 + + :param hostname: the hostname to check + :param trusted_list: a list of hostnames to check against. If a + hostname starts with a dot it will match against + all subdomains as well. + """ + if not hostname: + return False + + if isinstance(trusted_list, string_types): + trusted_list = [trusted_list] + + def _normalize(hostname): + if ':' in hostname: + hostname = hostname.rsplit(':', 1)[0] + return _encode_idna(hostname) + + try: + hostname = _normalize(hostname) + except UnicodeError: + return False + for ref in trusted_list: + if ref.startswith('.'): + ref = ref[1:] + suffix_match = True + else: + suffix_match = False + try: + ref = _normalize(ref) + except UnicodeError: + return False + if ref == hostname: + return True + if suffix_match and hostname.endswith(b'.' + ref): + return True + return False + + +def get_host(environ, trusted_hosts=None): + """Return the real host for the given WSGI environment. This first checks + the `X-Forwarded-Host` header, then the normal `Host` header, and finally + the `SERVER_NAME` environment variable (using the first one it finds). + + Optionally it verifies that the host is in a list of trusted hosts. + If the host is not in there it will raise a + :exc:`~werkzeug.exceptions.SecurityError`. + + :param environ: the WSGI environment to get the host of. + :param trusted_hosts: a list of trusted hosts, see :func:`host_is_trusted` + for more information. + """ + if 'HTTP_X_FORWARDED_HOST' in environ: + rv = environ['HTTP_X_FORWARDED_HOST'].split(',', 1)[0].strip() + elif 'HTTP_HOST' in environ: + rv = environ['HTTP_HOST'] + else: + rv = environ['SERVER_NAME'] + if (environ['wsgi.url_scheme'], environ['SERVER_PORT']) not \ + in (('https', '443'), ('http', '80')): + rv += ':' + environ['SERVER_PORT'] + if trusted_hosts is not None: + if not host_is_trusted(rv, trusted_hosts): + from werkzeug.exceptions import SecurityError + raise SecurityError('Host "%s" is not trusted' % rv) + return rv + + +def get_content_length(environ): + """Returns the content length from the WSGI environment as + integer. If it's not available or chunked transfer encoding is used, + ``None`` is returned. + + .. versionadded:: 0.9 + + :param environ: the WSGI environ to fetch the content length from. + """ + if environ.get('HTTP_TRANSFER_ENCODING', '') == 'chunked': + return None + + content_length = environ.get('CONTENT_LENGTH') + if content_length is not None: + try: + return max(0, int(content_length)) + except (ValueError, TypeError): + pass + + +def get_input_stream(environ, safe_fallback=True): + """Returns the input stream from the WSGI environment and wraps it + in the most sensible way possible. The stream returned is not the + raw WSGI stream in most cases but one that is safe to read from + without taking into account the content length. + + If content length is not set, the stream will be empty for safety reasons. + If the WSGI server supports chunked or infinite streams, it should set + the ``wsgi.input_terminated`` value in the WSGI environ to indicate that. + + .. versionadded:: 0.9 + + :param environ: the WSGI environ to fetch the stream from. + :param safe_fallback: use an empty stream as a safe fallback when the + content length is not set. Disabling this allows infinite streams, + which can be a denial-of-service risk. + """ + stream = environ['wsgi.input'] + content_length = get_content_length(environ) + + # A wsgi extension that tells us if the input is terminated. In + # that case we return the stream unchanged as we know we can safely + # read it until the end. + if environ.get('wsgi.input_terminated'): + return stream + + # If the request doesn't specify a content length, returning the stream is + # potentially dangerous because it could be infinite, malicious or not. If + # safe_fallback is true, return an empty stream instead for safety. + if content_length is None: + return safe_fallback and _empty_stream or stream + + # Otherwise limit the stream to the content length + return LimitedStream(stream, content_length) + + +def get_query_string(environ): + """Returns the `QUERY_STRING` from the WSGI environment. This also takes + care about the WSGI decoding dance on Python 3 environments as a + native string. The string returned will be restricted to ASCII + characters. + + .. versionadded:: 0.9 + + :param environ: the WSGI environment object to get the query string from. + """ + qs = wsgi_get_bytes(environ.get('QUERY_STRING', '')) + # QUERY_STRING really should be ascii safe but some browsers + # will send us some unicode stuff (I am looking at you IE). + # In that case we want to urllib quote it badly. + return try_coerce_native(url_quote(qs, safe=':&%=+$!*\'(),')) + + +def get_path_info(environ, charset='utf-8', errors='replace'): + """Returns the `PATH_INFO` from the WSGI environment and properly + decodes it. This also takes care about the WSGI decoding dance + on Python 3 environments. if the `charset` is set to `None` a + bytestring is returned. + + .. versionadded:: 0.9 + + :param environ: the WSGI environment object to get the path from. + :param charset: the charset for the path info, or `None` if no + decoding should be performed. + :param errors: the decoding error handling. + """ + path = wsgi_get_bytes(environ.get('PATH_INFO', '')) + return to_unicode(path, charset, errors, allow_none_charset=True) + + +def get_script_name(environ, charset='utf-8', errors='replace'): + """Returns the `SCRIPT_NAME` from the WSGI environment and properly + decodes it. This also takes care about the WSGI decoding dance + on Python 3 environments. if the `charset` is set to `None` a + bytestring is returned. + + .. versionadded:: 0.9 + + :param environ: the WSGI environment object to get the path from. + :param charset: the charset for the path, or `None` if no + decoding should be performed. + :param errors: the decoding error handling. + """ + path = wsgi_get_bytes(environ.get('SCRIPT_NAME', '')) + return to_unicode(path, charset, errors, allow_none_charset=True) + + +def pop_path_info(environ, charset='utf-8', errors='replace'): + """Removes and returns the next segment of `PATH_INFO`, pushing it onto + `SCRIPT_NAME`. Returns `None` if there is nothing left on `PATH_INFO`. + + If the `charset` is set to `None` a bytestring is returned. + + If there are empty segments (``'/foo//bar``) these are ignored but + properly pushed to the `SCRIPT_NAME`: + + >>> env = {'SCRIPT_NAME': '/foo', 'PATH_INFO': '/a/b'} + >>> pop_path_info(env) + 'a' + >>> env['SCRIPT_NAME'] + '/foo/a' + >>> pop_path_info(env) + 'b' + >>> env['SCRIPT_NAME'] + '/foo/a/b' + + .. versionadded:: 0.5 + + .. versionchanged:: 0.9 + The path is now decoded and a charset and encoding + parameter can be provided. + + :param environ: the WSGI environment that is modified. + """ + path = environ.get('PATH_INFO') + if not path: + return None + + script_name = environ.get('SCRIPT_NAME', '') + + # shift multiple leading slashes over + old_path = path + path = path.lstrip('/') + if path != old_path: + script_name += '/' * (len(old_path) - len(path)) + + if '/' not in path: + environ['PATH_INFO'] = '' + environ['SCRIPT_NAME'] = script_name + path + rv = wsgi_get_bytes(path) + else: + segment, path = path.split('/', 1) + environ['PATH_INFO'] = '/' + path + environ['SCRIPT_NAME'] = script_name + segment + rv = wsgi_get_bytes(segment) + + return to_unicode(rv, charset, errors, allow_none_charset=True) + + +def peek_path_info(environ, charset='utf-8', errors='replace'): + """Returns the next segment on the `PATH_INFO` or `None` if there + is none. Works like :func:`pop_path_info` without modifying the + environment: + + >>> env = {'SCRIPT_NAME': '/foo', 'PATH_INFO': '/a/b'} + >>> peek_path_info(env) + 'a' + >>> peek_path_info(env) + 'a' + + If the `charset` is set to `None` a bytestring is returned. + + .. versionadded:: 0.5 + + .. versionchanged:: 0.9 + The path is now decoded and a charset and encoding + parameter can be provided. + + :param environ: the WSGI environment that is checked. + """ + segments = environ.get('PATH_INFO', '').lstrip('/').split('/', 1) + if segments: + return to_unicode(wsgi_get_bytes(segments[0]), + charset, errors, allow_none_charset=True) + + +def extract_path_info(environ_or_baseurl, path_or_url, charset='utf-8', + errors='replace', collapse_http_schemes=True): + """Extracts the path info from the given URL (or WSGI environment) and + path. The path info returned is a unicode string, not a bytestring + suitable for a WSGI environment. The URLs might also be IRIs. + + If the path info could not be determined, `None` is returned. + + Some examples: + + >>> extract_path_info('http://example.com/app', '/app/hello') + u'/hello' + >>> extract_path_info('http://example.com/app', + ... 'https://example.com/app/hello') + u'/hello' + >>> extract_path_info('http://example.com/app', + ... 'https://example.com/app/hello', + ... collapse_http_schemes=False) is None + True + + Instead of providing a base URL you can also pass a WSGI environment. + + .. versionadded:: 0.6 + + :param environ_or_baseurl: a WSGI environment dict, a base URL or + base IRI. This is the root of the + application. + :param path_or_url: an absolute path from the server root, a + relative path (in which case it's the path info) + or a full URL. Also accepts IRIs and unicode + parameters. + :param charset: the charset for byte data in URLs + :param errors: the error handling on decode + :param collapse_http_schemes: if set to `False` the algorithm does + not assume that http and https on the + same server point to the same + resource. + """ + def _normalize_netloc(scheme, netloc): + parts = netloc.split(u'@', 1)[-1].split(u':', 1) + if len(parts) == 2: + netloc, port = parts + if (scheme == u'http' and port == u'80') or \ + (scheme == u'https' and port == u'443'): + port = None + else: + netloc = parts[0] + port = None + if port is not None: + netloc += u':' + port + return netloc + + # make sure whatever we are working on is a IRI and parse it + path = uri_to_iri(path_or_url, charset, errors) + if isinstance(environ_or_baseurl, dict): + environ_or_baseurl = get_current_url(environ_or_baseurl, + root_only=True) + base_iri = uri_to_iri(environ_or_baseurl, charset, errors) + base_scheme, base_netloc, base_path = url_parse(base_iri)[:3] + cur_scheme, cur_netloc, cur_path, = \ + url_parse(url_join(base_iri, path))[:3] + + # normalize the network location + base_netloc = _normalize_netloc(base_scheme, base_netloc) + cur_netloc = _normalize_netloc(cur_scheme, cur_netloc) + + # is that IRI even on a known HTTP scheme? + if collapse_http_schemes: + for scheme in base_scheme, cur_scheme: + if scheme not in (u'http', u'https'): + return None + else: + if not (base_scheme in (u'http', u'https') and + base_scheme == cur_scheme): + return None + + # are the netlocs compatible? + if base_netloc != cur_netloc: + return None + + # are we below the application path? + base_path = base_path.rstrip(u'/') + if not cur_path.startswith(base_path): + return None + + return u'/' + cur_path[len(base_path):].lstrip(u'/') + + +class ProxyMiddleware(object): + """This middleware routes some requests to the provided WSGI app and + proxies some requests to an external server. This is not something that + can generally be done on the WSGI layer and some HTTP requests will not + tunnel through correctly (for instance websocket requests cannot be + proxied through WSGI). As a result this is only really useful for some + basic requests that can be forwarded. + + Example configuration:: + + app = ProxyMiddleware(app, { + '/static/': { + 'target': 'http://127.0.0.1:5001/', + } + }) + + For each host options can be specified. The following options are + supported: + + ``target``: + the target URL to dispatch to + ``remove_prefix``: + if set to `True` the prefix is chopped off the URL before + dispatching it to the server. + ``host``: + When set to ``''`` which is the default the host header is + automatically rewritten to the URL of the target. If set to `None` + then the host header is unmodified from the client request. Any + other value overwrites the host header with that value. + ``headers``: + An optional dictionary of headers that should be sent with the + request to the target host. + ``ssl_context``: + In case this is an HTTPS target host then an SSL context can be + provided here (:class:`ssl.SSLContext`). This can be used for instance + to disable SSL verification. + + In this case everything below ``'/static/'`` is proxied to the server on + port 5001. The host header is automatically rewritten and so are request + URLs (eg: the leading `/static/` prefix here gets chopped off). + + .. versionadded:: 0.14 + """ + + def __init__(self, app, targets, chunk_size=2 << 13, timeout=10): + def _set_defaults(opts): + opts.setdefault('remove_prefix', False) + opts.setdefault('host', '') + opts.setdefault('headers', {}) + opts.setdefault('ssl_context', None) + return opts + self.app = app + self.targets = dict(('/%s/' % k.strip('/'), _set_defaults(v)) + for k, v in iteritems(targets)) + self.chunk_size = chunk_size + self.timeout = timeout + + def proxy_to(self, opts, path, prefix): + target = url_parse(opts['target']) + + def application(environ, start_response): + headers = list(EnvironHeaders(environ).items()) + headers[:] = [(k, v) for k, v in headers + if not is_hop_by_hop_header(k) and + k.lower() not in ('content-length', 'host')] + headers.append(('Connection', 'close')) + if opts['host'] == '': + headers.append(('Host', target.ascii_host)) + elif opts['host'] is None: + headers.append(('Host', environ['HTTP_HOST'])) + else: + headers.append(('Host', opts['host'])) + headers.extend(opts['headers'].items()) + + remote_path = path + if opts['remove_prefix']: + remote_path = '%s/%s' % ( + target.path.rstrip('/'), + remote_path[len(prefix):].lstrip('/') + ) + + content_length = environ.get('CONTENT_LENGTH') + chunked = False + if content_length not in ('', None): + headers.append(('Content-Length', content_length)) + elif content_length is not None: + headers.append(('Transfer-Encoding', 'chunked')) + chunked = True + + try: + if target.scheme == 'http': + con = httplib.HTTPConnection( + target.ascii_host, target.port or 80, + timeout=self.timeout) + elif target.scheme == 'https': + con = httplib.HTTPSConnection( + target.ascii_host, target.port or 443, + timeout=self.timeout, + context=opts['ssl_context']) + con.connect() + con.putrequest(environ['REQUEST_METHOD'], url_quote(remote_path), + skip_host=True) + + for k, v in headers: + if k.lower() == 'connection': + v = 'close' + con.putheader(k, v) + con.endheaders() + + stream = get_input_stream(environ) + while 1: + data = stream.read(self.chunk_size) + if not data: + break + if chunked: + con.send(b'%x\r\n%s\r\n' % (len(data), data)) + else: + con.send(data) + + resp = con.getresponse() + except socket.error: + from werkzeug.exceptions import BadGateway + return BadGateway()(environ, start_response) + + start_response('%d %s' % (resp.status, resp.reason), + [(k.title(), v) for k, v in resp.getheaders() + if not is_hop_by_hop_header(k)]) + + def read(): + while 1: + try: + data = resp.read(self.chunk_size) + except socket.error: + break + if not data: + break + yield data + return read() + return application + + def __call__(self, environ, start_response): + path = environ['PATH_INFO'] + app = self.app + for prefix, opts in iteritems(self.targets): + if path.startswith(prefix): + app = self.proxy_to(opts, path, prefix) + break + return app(environ, start_response) + + +class SharedDataMiddleware(object): + + """A WSGI middleware that provides static content for development + environments or simple server setups. Usage is quite simple:: + + import os + from werkzeug.wsgi import SharedDataMiddleware + + app = SharedDataMiddleware(app, { + '/shared': os.path.join(os.path.dirname(__file__), 'shared') + }) + + The contents of the folder ``./shared`` will now be available on + ``http://example.com/shared/``. This is pretty useful during development + because a standalone media server is not required. One can also mount + files on the root folder and still continue to use the application because + the shared data middleware forwards all unhandled requests to the + application, even if the requests are below one of the shared folders. + + If `pkg_resources` is available you can also tell the middleware to serve + files from package data:: + + app = SharedDataMiddleware(app, { + '/shared': ('myapplication', 'shared_files') + }) + + This will then serve the ``shared_files`` folder in the `myapplication` + Python package. + + The optional `disallow` parameter can be a list of :func:`~fnmatch.fnmatch` + rules for files that are not accessible from the web. If `cache` is set to + `False` no caching headers are sent. + + Currently the middleware does not support non ASCII filenames. If the + encoding on the file system happens to be the encoding of the URI it may + work but this could also be by accident. We strongly suggest using ASCII + only file names for static files. + + The middleware will guess the mimetype using the Python `mimetype` + module. If it's unable to figure out the charset it will fall back + to `fallback_mimetype`. + + .. versionchanged:: 0.5 + The cache timeout is configurable now. + + .. versionadded:: 0.6 + The `fallback_mimetype` parameter was added. + + :param app: the application to wrap. If you don't want to wrap an + application you can pass it :exc:`NotFound`. + :param exports: a list or dict of exported files and folders. + :param disallow: a list of :func:`~fnmatch.fnmatch` rules. + :param fallback_mimetype: the fallback mimetype for unknown files. + :param cache: enable or disable caching headers. + :param cache_timeout: the cache timeout in seconds for the headers. + """ + + def __init__(self, app, exports, disallow=None, cache=True, + cache_timeout=60 * 60 * 12, fallback_mimetype='text/plain'): + self.app = app + self.exports = [] + self.cache = cache + self.cache_timeout = cache_timeout + if hasattr(exports, 'items'): + exports = iteritems(exports) + for key, value in exports: + if isinstance(value, tuple): + loader = self.get_package_loader(*value) + elif isinstance(value, string_types): + if os.path.isfile(value): + loader = self.get_file_loader(value) + else: + loader = self.get_directory_loader(value) + else: + raise TypeError('unknown def %r' % value) + self.exports.append((key, loader)) + if disallow is not None: + from fnmatch import fnmatch + self.is_allowed = lambda x: not fnmatch(x, disallow) + self.fallback_mimetype = fallback_mimetype + + def is_allowed(self, filename): + """Subclasses can override this method to disallow the access to + certain files. However by providing `disallow` in the constructor + this method is overwritten. + """ + return True + + def _opener(self, filename): + return lambda: ( + open(filename, 'rb'), + datetime.utcfromtimestamp(os.path.getmtime(filename)), + int(os.path.getsize(filename)) + ) + + def get_file_loader(self, filename): + return lambda x: (os.path.basename(filename), self._opener(filename)) + + def get_package_loader(self, package, package_path): + from pkg_resources import DefaultProvider, ResourceManager, \ + get_provider + loadtime = datetime.utcnow() + provider = get_provider(package) + manager = ResourceManager() + filesystem_bound = isinstance(provider, DefaultProvider) + + def loader(path): + if path is None: + return None, None + path = posixpath.join(package_path, path) + if not provider.has_resource(path): + return None, None + basename = posixpath.basename(path) + if filesystem_bound: + return basename, self._opener( + provider.get_resource_filename(manager, path)) + s = provider.get_resource_string(manager, path) + return basename, lambda: ( + BytesIO(s), + loadtime, + len(s) + ) + return loader + + def get_directory_loader(self, directory): + def loader(path): + if path is not None: + path = os.path.join(directory, path) + else: + path = directory + if os.path.isfile(path): + return os.path.basename(path), self._opener(path) + return None, None + return loader + + def generate_etag(self, mtime, file_size, real_filename): + if not isinstance(real_filename, bytes): + real_filename = real_filename.encode(get_filesystem_encoding()) + return 'wzsdm-%d-%s-%s' % ( + mktime(mtime.timetuple()), + file_size, + adler32(real_filename) & 0xffffffff + ) + + def __call__(self, environ, start_response): + cleaned_path = get_path_info(environ) + if PY2: + cleaned_path = cleaned_path.encode(get_filesystem_encoding()) + # sanitize the path for non unix systems + cleaned_path = cleaned_path.strip('/') + for sep in os.sep, os.altsep: + if sep and sep != '/': + cleaned_path = cleaned_path.replace(sep, '/') + path = '/' + '/'.join(x for x in cleaned_path.split('/') + if x and x != '..') + file_loader = None + for search_path, loader in self.exports: + if search_path == path: + real_filename, file_loader = loader(None) + if file_loader is not None: + break + if not search_path.endswith('/'): + search_path += '/' + if path.startswith(search_path): + real_filename, file_loader = loader(path[len(search_path):]) + if file_loader is not None: + break + if file_loader is None or not self.is_allowed(real_filename): + return self.app(environ, start_response) + + guessed_type = mimetypes.guess_type(real_filename) + mime_type = guessed_type[0] or self.fallback_mimetype + f, mtime, file_size = file_loader() + + headers = [('Date', http_date())] + if self.cache: + timeout = self.cache_timeout + etag = self.generate_etag(mtime, file_size, real_filename) + headers += [ + ('Etag', '"%s"' % etag), + ('Cache-Control', 'max-age=%d, public' % timeout) + ] + if not is_resource_modified(environ, etag, last_modified=mtime): + f.close() + start_response('304 Not Modified', headers) + return [] + headers.append(('Expires', http_date(time() + timeout))) + else: + headers.append(('Cache-Control', 'public')) + + headers.extend(( + ('Content-Type', mime_type), + ('Content-Length', str(file_size)), + ('Last-Modified', http_date(mtime)) + )) + start_response('200 OK', headers) + return wrap_file(environ, f) + + +class DispatcherMiddleware(object): + + """Allows one to mount middlewares or applications in a WSGI application. + This is useful if you want to combine multiple WSGI applications:: + + app = DispatcherMiddleware(app, { + '/app2': app2, + '/app3': app3 + }) + """ + + def __init__(self, app, mounts=None): + self.app = app + self.mounts = mounts or {} + + def __call__(self, environ, start_response): + script = environ.get('PATH_INFO', '') + path_info = '' + while '/' in script: + if script in self.mounts: + app = self.mounts[script] + break + script, last_item = script.rsplit('/', 1) + path_info = '/%s%s' % (last_item, path_info) + else: + app = self.mounts.get(script, self.app) + original_script_name = environ.get('SCRIPT_NAME', '') + environ['SCRIPT_NAME'] = original_script_name + script + environ['PATH_INFO'] = path_info + return app(environ, start_response) + + +@implements_iterator +class ClosingIterator(object): + + """The WSGI specification requires that all middlewares and gateways + respect the `close` callback of an iterator. Because it is useful to add + another close action to a returned iterator and adding a custom iterator + is a boring task this class can be used for that:: + + return ClosingIterator(app(environ, start_response), [cleanup_session, + cleanup_locals]) + + If there is just one close function it can be passed instead of the list. + + A closing iterator is not needed if the application uses response objects + and finishes the processing if the response is started:: + + try: + return response(environ, start_response) + finally: + cleanup_session() + cleanup_locals() + """ + + def __init__(self, iterable, callbacks=None): + iterator = iter(iterable) + self._next = partial(next, iterator) + if callbacks is None: + callbacks = [] + elif callable(callbacks): + callbacks = [callbacks] + else: + callbacks = list(callbacks) + iterable_close = getattr(iterator, 'close', None) + if iterable_close: + callbacks.insert(0, iterable_close) + self._callbacks = callbacks + + def __iter__(self): + return self + + def __next__(self): + return self._next() + + def close(self): + for callback in self._callbacks: + callback() + + +def wrap_file(environ, file, buffer_size=8192): + """Wraps a file. This uses the WSGI server's file wrapper if available + or otherwise the generic :class:`FileWrapper`. + + .. versionadded:: 0.5 + + If the file wrapper from the WSGI server is used it's important to not + iterate over it from inside the application but to pass it through + unchanged. If you want to pass out a file wrapper inside a response + object you have to set :attr:`~BaseResponse.direct_passthrough` to `True`. + + More information about file wrappers are available in :pep:`333`. + + :param file: a :class:`file`-like object with a :meth:`~file.read` method. + :param buffer_size: number of bytes for one iteration. + """ + return environ.get('wsgi.file_wrapper', FileWrapper)(file, buffer_size) + + +@implements_iterator +class FileWrapper(object): + + """This class can be used to convert a :class:`file`-like object into + an iterable. It yields `buffer_size` blocks until the file is fully + read. + + You should not use this class directly but rather use the + :func:`wrap_file` function that uses the WSGI server's file wrapper + support if it's available. + + .. versionadded:: 0.5 + + If you're using this object together with a :class:`BaseResponse` you have + to use the `direct_passthrough` mode. + + :param file: a :class:`file`-like object with a :meth:`~file.read` method. + :param buffer_size: number of bytes for one iteration. + """ + + def __init__(self, file, buffer_size=8192): + self.file = file + self.buffer_size = buffer_size + + def close(self): + if hasattr(self.file, 'close'): + self.file.close() + + def seekable(self): + if hasattr(self.file, 'seekable'): + return self.file.seekable() + if hasattr(self.file, 'seek'): + return True + return False + + def seek(self, *args): + if hasattr(self.file, 'seek'): + self.file.seek(*args) + + def tell(self): + if hasattr(self.file, 'tell'): + return self.file.tell() + return None + + def __iter__(self): + return self + + def __next__(self): + data = self.file.read(self.buffer_size) + if data: + return data + raise StopIteration() + + +@implements_iterator +class _RangeWrapper(object): + # private for now, but should we make it public in the future ? + + """This class can be used to convert an iterable object into + an iterable that will only yield a piece of the underlying content. + It yields blocks until the underlying stream range is fully read. + The yielded blocks will have a size that can't exceed the original + iterator defined block size, but that can be smaller. + + If you're using this object together with a :class:`BaseResponse` you have + to use the `direct_passthrough` mode. + + :param iterable: an iterable object with a :meth:`__next__` method. + :param start_byte: byte from which read will start. + :param byte_range: how many bytes to read. + """ + + def __init__(self, iterable, start_byte=0, byte_range=None): + self.iterable = iter(iterable) + self.byte_range = byte_range + self.start_byte = start_byte + self.end_byte = None + if byte_range is not None: + self.end_byte = self.start_byte + self.byte_range + self.read_length = 0 + self.seekable = hasattr(iterable, 'seekable') and iterable.seekable() + self.end_reached = False + + def __iter__(self): + return self + + def _next_chunk(self): + try: + chunk = next(self.iterable) + self.read_length += len(chunk) + return chunk + except StopIteration: + self.end_reached = True + raise + + def _first_iteration(self): + chunk = None + if self.seekable: + self.iterable.seek(self.start_byte) + self.read_length = self.iterable.tell() + contextual_read_length = self.read_length + else: + while self.read_length <= self.start_byte: + chunk = self._next_chunk() + if chunk is not None: + chunk = chunk[self.start_byte - self.read_length:] + contextual_read_length = self.start_byte + return chunk, contextual_read_length + + def _next(self): + if self.end_reached: + raise StopIteration() + chunk = None + contextual_read_length = self.read_length + if self.read_length == 0: + chunk, contextual_read_length = self._first_iteration() + if chunk is None: + chunk = self._next_chunk() + if self.end_byte is not None and self.read_length >= self.end_byte: + self.end_reached = True + return chunk[:self.end_byte - contextual_read_length] + return chunk + + def __next__(self): + chunk = self._next() + if chunk: + return chunk + self.end_reached = True + raise StopIteration() + + def close(self): + if hasattr(self.iterable, 'close'): + self.iterable.close() + + +def _make_chunk_iter(stream, limit, buffer_size): + """Helper for the line and chunk iter functions.""" + if isinstance(stream, (bytes, bytearray, text_type)): + raise TypeError('Passed a string or byte object instead of ' + 'true iterator or stream.') + if not hasattr(stream, 'read'): + for item in stream: + if item: + yield item + return + if not isinstance(stream, LimitedStream) and limit is not None: + stream = LimitedStream(stream, limit) + _read = stream.read + while 1: + item = _read(buffer_size) + if not item: + break + yield item + + +def make_line_iter(stream, limit=None, buffer_size=10 * 1024, + cap_at_buffer=False): + """Safely iterates line-based over an input stream. If the input stream + is not a :class:`LimitedStream` the `limit` parameter is mandatory. + + This uses the stream's :meth:`~file.read` method internally as opposite + to the :meth:`~file.readline` method that is unsafe and can only be used + in violation of the WSGI specification. The same problem applies to the + `__iter__` function of the input stream which calls :meth:`~file.readline` + without arguments. + + If you need line-by-line processing it's strongly recommended to iterate + over the input stream using this helper function. + + .. versionchanged:: 0.8 + This function now ensures that the limit was reached. + + .. versionadded:: 0.9 + added support for iterators as input stream. + + .. versionadded:: 0.11.10 + added support for the `cap_at_buffer` parameter. + + :param stream: the stream or iterate to iterate over. + :param limit: the limit in bytes for the stream. (Usually + content length. Not necessary if the `stream` + is a :class:`LimitedStream`. + :param buffer_size: The optional buffer size. + :param cap_at_buffer: if this is set chunks are split if they are longer + than the buffer size. Internally this is implemented + that the buffer size might be exhausted by a factor + of two however. + """ + _iter = _make_chunk_iter(stream, limit, buffer_size) + + first_item = next(_iter, '') + if not first_item: + return + + s = make_literal_wrapper(first_item) + empty = s('') + cr = s('\r') + lf = s('\n') + crlf = s('\r\n') + + _iter = chain((first_item,), _iter) + + def _iter_basic_lines(): + _join = empty.join + buffer = [] + while 1: + new_data = next(_iter, '') + if not new_data: + break + new_buf = [] + buf_size = 0 + for item in chain(buffer, new_data.splitlines(True)): + new_buf.append(item) + buf_size += len(item) + if item and item[-1:] in crlf: + yield _join(new_buf) + new_buf = [] + elif cap_at_buffer and buf_size >= buffer_size: + rv = _join(new_buf) + while len(rv) >= buffer_size: + yield rv[:buffer_size] + rv = rv[buffer_size:] + new_buf = [rv] + buffer = new_buf + if buffer: + yield _join(buffer) + + # This hackery is necessary to merge 'foo\r' and '\n' into one item + # of 'foo\r\n' if we were unlucky and we hit a chunk boundary. + previous = empty + for item in _iter_basic_lines(): + if item == lf and previous[-1:] == cr: + previous += item + item = empty + if previous: + yield previous + previous = item + if previous: + yield previous + + +def make_chunk_iter(stream, separator, limit=None, buffer_size=10 * 1024, + cap_at_buffer=False): + """Works like :func:`make_line_iter` but accepts a separator + which divides chunks. If you want newline based processing + you should use :func:`make_line_iter` instead as it + supports arbitrary newline markers. + + .. versionadded:: 0.8 + + .. versionadded:: 0.9 + added support for iterators as input stream. + + .. versionadded:: 0.11.10 + added support for the `cap_at_buffer` parameter. + + :param stream: the stream or iterate to iterate over. + :param separator: the separator that divides chunks. + :param limit: the limit in bytes for the stream. (Usually + content length. Not necessary if the `stream` + is otherwise already limited). + :param buffer_size: The optional buffer size. + :param cap_at_buffer: if this is set chunks are split if they are longer + than the buffer size. Internally this is implemented + that the buffer size might be exhausted by a factor + of two however. + """ + _iter = _make_chunk_iter(stream, limit, buffer_size) + + first_item = next(_iter, '') + if not first_item: + return + + _iter = chain((first_item,), _iter) + if isinstance(first_item, text_type): + separator = to_unicode(separator) + _split = re.compile(r'(%s)' % re.escape(separator)).split + _join = u''.join + else: + separator = to_bytes(separator) + _split = re.compile(b'(' + re.escape(separator) + b')').split + _join = b''.join + + buffer = [] + while 1: + new_data = next(_iter, '') + if not new_data: + break + chunks = _split(new_data) + new_buf = [] + buf_size = 0 + for item in chain(buffer, chunks): + if item == separator: + yield _join(new_buf) + new_buf = [] + buf_size = 0 + else: + buf_size += len(item) + new_buf.append(item) + + if cap_at_buffer and buf_size >= buffer_size: + rv = _join(new_buf) + while len(rv) >= buffer_size: + yield rv[:buffer_size] + rv = rv[buffer_size:] + new_buf = [rv] + buf_size = len(rv) + + buffer = new_buf + if buffer: + yield _join(buffer) + + +@implements_iterator +class LimitedStream(io.IOBase): + + """Wraps a stream so that it doesn't read more than n bytes. If the + stream is exhausted and the caller tries to get more bytes from it + :func:`on_exhausted` is called which by default returns an empty + string. The return value of that function is forwarded + to the reader function. So if it returns an empty string + :meth:`read` will return an empty string as well. + + The limit however must never be higher than what the stream can + output. Otherwise :meth:`readlines` will try to read past the + limit. + + .. admonition:: Note on WSGI compliance + + calls to :meth:`readline` and :meth:`readlines` are not + WSGI compliant because it passes a size argument to the + readline methods. Unfortunately the WSGI PEP is not safely + implementable without a size argument to :meth:`readline` + because there is no EOF marker in the stream. As a result + of that the use of :meth:`readline` is discouraged. + + For the same reason iterating over the :class:`LimitedStream` + is not portable. It internally calls :meth:`readline`. + + We strongly suggest using :meth:`read` only or using the + :func:`make_line_iter` which safely iterates line-based + over a WSGI input stream. + + :param stream: the stream to wrap. + :param limit: the limit for the stream, must not be longer than + what the string can provide if the stream does not + end with `EOF` (like `wsgi.input`) + """ + + def __init__(self, stream, limit): + self._read = stream.read + self._readline = stream.readline + self._pos = 0 + self.limit = limit + + def __iter__(self): + return self + + @property + def is_exhausted(self): + """If the stream is exhausted this attribute is `True`.""" + return self._pos >= self.limit + + def on_exhausted(self): + """This is called when the stream tries to read past the limit. + The return value of this function is returned from the reading + function. + """ + # Read null bytes from the stream so that we get the + # correct end of stream marker. + return self._read(0) + + def on_disconnect(self): + """What should happen if a disconnect is detected? The return + value of this function is returned from read functions in case + the client went away. By default a + :exc:`~werkzeug.exceptions.ClientDisconnected` exception is raised. + """ + from werkzeug.exceptions import ClientDisconnected + raise ClientDisconnected() + + def exhaust(self, chunk_size=1024 * 64): + """Exhaust the stream. This consumes all the data left until the + limit is reached. + + :param chunk_size: the size for a chunk. It will read the chunk + until the stream is exhausted and throw away + the results. + """ + to_read = self.limit - self._pos + chunk = chunk_size + while to_read > 0: + chunk = min(to_read, chunk) + self.read(chunk) + to_read -= chunk + + def read(self, size=None): + """Read `size` bytes or if size is not provided everything is read. + + :param size: the number of bytes read. + """ + if self._pos >= self.limit: + return self.on_exhausted() + if size is None or size == -1: # -1 is for consistence with file + size = self.limit + to_read = min(self.limit - self._pos, size) + try: + read = self._read(to_read) + except (IOError, ValueError): + return self.on_disconnect() + if to_read and len(read) != to_read: + return self.on_disconnect() + self._pos += len(read) + return read + + def readline(self, size=None): + """Reads one line from the stream.""" + if self._pos >= self.limit: + return self.on_exhausted() + if size is None: + size = self.limit - self._pos + else: + size = min(size, self.limit - self._pos) + try: + line = self._readline(size) + except (ValueError, IOError): + return self.on_disconnect() + if size and not line: + return self.on_disconnect() + self._pos += len(line) + return line + + def readlines(self, size=None): + """Reads a file into a list of strings. It calls :meth:`readline` + until the file is read to the end. It does support the optional + `size` argument if the underlaying stream supports it for + `readline`. + """ + last_pos = self._pos + result = [] + if size is not None: + end = min(self.limit, last_pos + size) + else: + end = self.limit + while 1: + if size is not None: + size -= last_pos - self._pos + if self._pos >= end: + break + result.append(self.readline(size)) + if size is not None: + last_pos = self._pos + return result + + def tell(self): + """Returns the position of the stream. + + .. versionadded:: 0.9 + """ + return self._pos + + def __next__(self): + line = self.readline() + if not line: + raise StopIteration() + return line + + def readable(self): + return True diff --git a/requirements_openpilot.txt b/requirements_openpilot.txt index 7d2c68452d1427..deb37d08655808 100644 --- a/requirements_openpilot.txt +++ b/requirements_openpilot.txt @@ -1,14 +1,19 @@ -Cython==0.24.1 +Cython==0.27.3 bitstring==3.1.5 -fastcluster==1.1.21 +fastcluster==1.1.20 libusb1==1.5.0 -pycapnp==0.5.9 +pycapnp==0.6.3 pyzmq==15.4.0 raven==5.23.0 requests==2.10.0 setproctitle==1.1.10 simplejson==3.8.2 pyyaml==3.12 -cffi==1.7.0 -enum34==1.1.1 --e git+https://github.com/commaai/le_python.git#egg=Logentries +cffi==1.11.5 +enum34==1.1.6 +sympy==1.1.1 +filterpy==1.2.4 +smbus2==0.2.0 +pyflakes==1.6.0 +-e git+https://github.com/commaai/le_python.git@5eef8f5be5929d33973e1b10e686fa0cdcd6792f#egg=Logentries +Flask==1.0.2 diff --git a/selfdrive/assets/OpenSans-Bold.ttf b/selfdrive/assets/OpenSans-Bold.ttf new file mode 100644 index 00000000000000..7b529456032abf Binary files /dev/null and b/selfdrive/assets/OpenSans-Bold.ttf differ diff --git a/selfdrive/assets/img_chffr_wheel.png b/selfdrive/assets/img_chffr_wheel.png new file mode 100644 index 00000000000000..3f09a35a79bf45 Binary files /dev/null and b/selfdrive/assets/img_chffr_wheel.png differ diff --git a/selfdrive/assets/img_driver_face.png b/selfdrive/assets/img_driver_face.png new file mode 100644 index 00000000000000..ddde478cd789ec Binary files /dev/null and b/selfdrive/assets/img_driver_face.png differ diff --git a/selfdrive/assets/img_spinner_comma.png b/selfdrive/assets/img_spinner_comma.png new file mode 100644 index 00000000000000..16109557f85911 Binary files /dev/null and b/selfdrive/assets/img_spinner_comma.png differ diff --git a/selfdrive/assets/img_spinner_track.png b/selfdrive/assets/img_spinner_track.png new file mode 100644 index 00000000000000..931c17e8367cef Binary files /dev/null and b/selfdrive/assets/img_spinner_track.png differ diff --git a/selfdrive/assets/img_trafficLight_green.png b/selfdrive/assets/img_trafficLight_green.png new file mode 100644 index 00000000000000..b2e07dab0323cc Binary files /dev/null and b/selfdrive/assets/img_trafficLight_green.png differ diff --git a/selfdrive/assets/img_trafficLight_none.png b/selfdrive/assets/img_trafficLight_none.png new file mode 100644 index 00000000000000..01deb5a009980a Binary files /dev/null and b/selfdrive/assets/img_trafficLight_none.png differ diff --git a/selfdrive/assets/img_trafficLight_red.png b/selfdrive/assets/img_trafficLight_red.png new file mode 100644 index 00000000000000..4c440250e4e1c7 Binary files /dev/null and b/selfdrive/assets/img_trafficLight_red.png differ diff --git a/selfdrive/assets/img_trafficLight_yellow.png b/selfdrive/assets/img_trafficLight_yellow.png new file mode 100644 index 00000000000000..8dd5bd42c37a33 Binary files /dev/null and b/selfdrive/assets/img_trafficLight_yellow.png differ diff --git a/selfdrive/assets/img_trafficSign_stop.png b/selfdrive/assets/img_trafficSign_stop.png new file mode 100644 index 00000000000000..9261c47472e9a5 Binary files /dev/null and b/selfdrive/assets/img_trafficSign_stop.png differ diff --git a/selfdrive/assets/sounds/disengaged.wav b/selfdrive/assets/sounds/disengaged.wav new file mode 100644 index 00000000000000..958e08fd85b3e6 Binary files /dev/null and b/selfdrive/assets/sounds/disengaged.wav differ diff --git a/selfdrive/assets/sounds/engaged.wav b/selfdrive/assets/sounds/engaged.wav new file mode 100644 index 00000000000000..c6c088e01c8b73 Binary files /dev/null and b/selfdrive/assets/sounds/engaged.wav differ diff --git a/selfdrive/assets/sounds/error.wav b/selfdrive/assets/sounds/error.wav new file mode 100644 index 00000000000000..1ff0c540d26ab0 Binary files /dev/null and b/selfdrive/assets/sounds/error.wav differ diff --git a/selfdrive/assets/sounds/warning_1.wav b/selfdrive/assets/sounds/warning_1.wav new file mode 100644 index 00000000000000..67b8d76fe804fa Binary files /dev/null and b/selfdrive/assets/sounds/warning_1.wav differ diff --git a/selfdrive/assets/sounds/warning_2.wav b/selfdrive/assets/sounds/warning_2.wav new file mode 100644 index 00000000000000..8e1b1d7d9161a7 Binary files /dev/null and b/selfdrive/assets/sounds/warning_2.wav differ diff --git a/selfdrive/boardd/Makefile b/selfdrive/boardd/Makefile index 1573304e673498..893edde545b848 100644 --- a/selfdrive/boardd/Makefile +++ b/selfdrive/boardd/Makefile @@ -13,8 +13,8 @@ WARN_FLAGS = -Werror=implicit-function-declaration \ -Werror=return-type \ -Werror=format-extra-args -CFLAGS = -std=gnu11 -g -fPIC -I../../ -O2 $(WARN_FLAGS) -CXXFLAGS = -std=c++11 -g -fPIC -I../../ -O2 $(WARN_FLAGS) +CFLAGS = -std=gnu11 -g -fPIC -I../ -I../../ -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -I../ -I../../ -O2 $(WARN_FLAGS) ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 285134de9e3320..aae2b665aec1bb 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -25,6 +25,8 @@ #include "common/swaglog.h" #include "common/timing.h" +#include + // double the FIFO size #define RECV_SIZE (0x1000) #define TIMEOUT 0 @@ -33,6 +35,16 @@ #define SAFETY_HONDA 1 #define SAFETY_TOYOTA 2 #define SAFETY_ELM327 0xE327 +#define SAFETY_GM 3 +#define SAFETY_HONDA_BOSCH 4 +#define SAFETY_FORD 5 +#define SAFETY_CADILLAC 6 +#define SAFETY_HYUNDAI 7 +#define SAFETY_TESLA 8 +#define SAFETY_TOYOTA_IPAS 0x1335 +#define SAFETY_TOYOTA_NOLIMITS 0x1336 +#define SAFETY_ALLOUTPUT 0x1337 +#define SAFETY_ELM327 0xE327 namespace { @@ -45,8 +57,14 @@ pthread_mutex_t usb_lock; bool spoofing_started = false; bool fake_send = false; bool loopback_can = false; +bool is_grey_panda = false; pthread_t safety_setter_thread_handle = -1; +pthread_t pigeon_thread_handle = -1; +bool pigeon_needs_init; + +void pigeon_init(); +void *pigeon_thread(void *crap); void *safety_setter_thread(void *s) { char *value; @@ -70,7 +88,8 @@ void *safety_setter_thread(void *s) { cereal::CarParams::Reader car_params = cmsg.getRoot(); auto safety_model = car_params.getSafetyModel(); - LOGW("setting safety model: %d", safety_model); + auto safety_param = car_params.getSafetyParam(); + LOGW("setting safety model: %d with param %d", safety_model, safety_param); int safety_setting = 0; switch (safety_model) { @@ -86,6 +105,21 @@ void *safety_setter_thread(void *s) { case (int)cereal::CarParams::SafetyModels::ELM327: safety_setting = SAFETY_ELM327; break; + case (int)cereal::CarParams::SafetyModels::GM: + safety_setting = SAFETY_GM; + break; + case (int)cereal::CarParams::SafetyModels::HONDA_BOSCH: + safety_setting = SAFETY_HONDA_BOSCH; + break; + case (int)cereal::CarParams::SafetyModels::FORD: + safety_setting = SAFETY_FORD; + break; + case (int)cereal::CarParams::SafetyModels::CADILLAC: + safety_setting = SAFETY_CADILLAC; + break; + case (int)cereal::CarParams::SafetyModels::HYUNDAI: + safety_setting = SAFETY_HYUNDAI; + break; default: LOGE("unknown safety model: %d", safety_model); } @@ -95,7 +129,7 @@ void *safety_setter_thread(void *s) { // set in the mutex to avoid race safety_setter_thread_handle = -1; - libusb_control_transfer(dev_handle, 0x40, 0xdc, safety_setting, 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xdc, safety_setting, safety_param, NULL, 0, TIMEOUT); pthread_mutex_unlock(&usb_lock); @@ -105,6 +139,7 @@ void *safety_setter_thread(void *s) { // must be called before threads or with mutex bool usb_connect() { int err; + unsigned char is_pigeon[1] = {0}; dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); if (dev_handle == NULL) { goto fail; } @@ -138,6 +173,19 @@ bool usb_connect() { if (safety_setter_thread_handle == -1) { err = pthread_create(&safety_setter_thread_handle, NULL, safety_setter_thread, NULL); + assert(err == 0); + } + + libusb_control_transfer(dev_handle, 0xc0, 0xc1, 0, 0, is_pigeon, 1, TIMEOUT); + + if (is_pigeon[0]) { + LOGW("grey panda detected"); + is_grey_panda = true; + pigeon_needs_init = true; + if (pigeon_thread_handle == -1) { + err = pthread_create(&pigeon_thread_handle, NULL, pigeon_thread, NULL); + assert(err == 0); + } } return true; @@ -255,6 +303,7 @@ void can_health(void *s) { healthData.setControlsAllowed(health.controls_allowed); healthData.setGasInterceptorDetected(health.gas_interceptor_detected); healthData.setStartedSignalDetected(health.started_signal_detected); + healthData.setIsGreyPanda(is_grey_panda); // send to health auto words = capnp::messageToFlatArray(msg); @@ -352,6 +401,8 @@ void *thermal_thread(void *crap) { pthread_mutex_lock(&usb_lock); libusb_control_transfer(dev_handle, 0xc0, 0xd3, target_fan_speed, 0, NULL, 0, TIMEOUT); pthread_mutex_unlock(&usb_lock); + + zmq_msg_close(&msg); } // turn the fan off when we exit @@ -409,6 +460,154 @@ void *can_health_thread(void *crap) { return NULL; } +#define pigeon_send(x) _pigeon_send(x, sizeof(x)-1) + +void hexdump(unsigned char *d, int l) { + for (int i = 0; i < l; i++) { + if (i!=0 && i%0x10 == 0) printf("\n"); + printf("%2.2X ", d[i]); + } + printf("\n"); +} + +void _pigeon_send(const char *dat, int len) { + int sent; + unsigned char a[0x20]; + int err; + a[0] = 1; + for (int i=0; i(); + event.setLogMonoTime(nanos_since_boot()); + auto ublox_raw = event.initUbloxRaw(alen); + memcpy(ublox_raw.begin(), dat, alen); + + // send to ubloxRaw + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); +} + + +void *pigeon_thread(void *crap) { + // ubloxRaw = 8042 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8042"); + + // run at ~100hz + unsigned char dat[0x1000]; + uint64_t cnt = 0; + while (!do_exit) { + if (pigeon_needs_init) { + pigeon_needs_init = false; + pigeon_init(); + } + int alen = 0; + while (alen < 0xfc0) { + pthread_mutex_lock(&usb_lock); + int len = libusb_control_transfer(dev_handle, 0xc0, 0xe0, 1, 0, dat+alen, 0x40, TIMEOUT); + if (len < 0) { handle_usb_issue(len, __func__); } + pthread_mutex_unlock(&usb_lock); + if (len <= 0) break; + + //printf("got %d\n", len); + alen += len; + } + if (alen > 0) { + if (dat[0] == (char)0x00){ + LOGW("received invalid ublox message, resetting pigeon"); + pigeon_init(); + } else { + pigeon_publish_raw(publisher, dat, alen); + } + } + + // 10ms + usleep(10*1000); + cnt++; + } + + return NULL; +} + int set_realtime_priority(int level) { // should match python using chrt struct sched_param sa; @@ -436,7 +635,7 @@ int main() { fake_send = true; } - if(getenv("BOARDD_LOOPBACK")){ + if (getenv("BOARDD_LOOPBACK")){ loopback_can = true; } @@ -484,6 +683,8 @@ int main() { err = pthread_join(can_health_thread_handle, NULL); assert(err == 0); + //while (!do_exit) usleep(1000); + // destruct libusb libusb_close(dev_handle); diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py index 0b428d04ee6ff2..d897a815f2cb03 100755 --- a/selfdrive/boardd/boardd.py +++ b/selfdrive/boardd/boardd.py @@ -1,4 +1,8 @@ #!/usr/bin/env python + +# TODO: merge the extra functionalities of this file (like MOCK) in boardd.c and +# delete this python version of boardd + import os import struct import zmq @@ -12,12 +16,10 @@ # USB is optional try: import usb1 - from usb1 import USBErrorIO, USBErrorOverflow + from usb1 import USBErrorIO, USBErrorOverflow #pylint: disable=no-name-in-module except Exception: pass -# TODO: rewrite in C to save CPU - SAFETY_NOOUTPUT = 0 SAFETY_HONDA = 1 SAFETY_TOYOTA = 2 @@ -101,13 +103,13 @@ def can_init(): if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc: handle = device.open() handle.claimInterface(0) - handle.controlWrite(0x40, 0xdc, SAFETY_HONDA, 0, b'') + handle.controlWrite(0x40, 0xdc, SAFETY_ALLOUTPUT, 0, b'') if handle is None: - print "CAN NOT FOUND" + cloudlog.warn("CAN NOT FOUND") exit(-1) - print "got handle" + cloudlog.info("got handle") cloudlog.info("can init done") def boardd_mock_loop(): @@ -129,7 +131,7 @@ def boardd_mock_loop(): # recv @ 100hz can_msgs = can_recv() - print "sent %d got %d" % (len(snd), len(can_msgs)) + print("sent %d got %d" % (len(snd), len(can_msgs))) m = can_list_to_can_capnp(can_msgs) sendcan.send(m.to_bytes()) @@ -142,7 +144,7 @@ def boardd_test_loop(): #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",1]]) # recv @ 100hz can_msgs = can_recv() - print "got %d" % (len(can_msgs)) + print("got %d" % (len(can_msgs))) time.sleep(0.01) cnt += 1 diff --git a/selfdrive/can/Makefile b/selfdrive/can/Makefile index 8a1c6f6b7aa644..b140aa5f87e2a1 100644 --- a/selfdrive/can/Makefile +++ b/selfdrive/can/Makefile @@ -28,6 +28,7 @@ else ifeq ($(UNAME_M),x86_64) else ifeq ($(UNAME_M),aarch64) ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib -l:libzmq.a + CXXFLAGS += -lgnustl_shared endif OPENDBC_PATH := $(shell python -c 'import opendbc; print opendbc.DBC_PATH') @@ -65,3 +66,5 @@ dbc_out/%.cc: $(OPENDBC_PATH)/%.dbc process_dbc.py dbc_template.cc clean: rm -rf libdbc.so* rm -f dbc_out/*.cc + rm -f dbcs.txt + rm -f dbcs.csv diff --git a/selfdrive/can/common.h b/selfdrive/can/common.h index 6c4db60496fe1e..f8d07ae681f760 100644 --- a/selfdrive/can/common.h +++ b/selfdrive/can/common.h @@ -8,6 +8,8 @@ #define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) +unsigned int honda_checksum(unsigned int address, uint64_t d, int l); +unsigned int toyota_checksum(unsigned int address, uint64_t d, int l); struct SignalPackValue { const char* name; @@ -46,6 +48,7 @@ struct Signal { int b1, b2, bo; bool is_signed; double factor, offset; + bool is_little_endian; SignalType type; }; @@ -57,10 +60,19 @@ struct Msg { const Signal *sigs; }; +struct Val { + const char* name; + uint32_t address; + const char* def_val; + const Signal *sigs; +}; + struct DBC { const char* name; size_t num_msgs; const Msg *msgs; + const Val *vals; + size_t num_vals; }; const DBC* dbc_lookup(const std::string& dbc_name); diff --git a/selfdrive/can/dbc.cc b/selfdrive/can/dbc.cc index c8295d1e0c8157..95d5e4d791394a 100644 --- a/selfdrive/can/dbc.cc +++ b/selfdrive/can/dbc.cc @@ -24,3 +24,9 @@ const DBC* dbc_lookup(const std::string& dbc_name) { void dbc_register(const DBC* dbc) { get_dbcs().push_back(dbc); } + +extern "C" { + const DBC* dbc_lookup(const char* dbc_name) { + return dbc_lookup(std::string(dbc_name)); + } +} diff --git a/selfdrive/can/dbc_template.cc b/selfdrive/can/dbc_template.cc index 7d15691545edc5..2d4fb9570a0170 100644 --- a/selfdrive/can/dbc_template.cc +++ b/selfdrive/can/dbc_template.cc @@ -8,7 +8,11 @@ namespace { const Signal sigs_{{address}}[] = { {% for sig in sigs %} { - {% set b1 = (sig.start_bit//8)*8 + (-sig.start_bit-1) % 8 %} + {% if sig.is_little_endian %} + {% set b1 = sig.start_bit %} + {% else %} + {% set b1 = (sig.start_bit//8)*8 + (-sig.start_bit-1) % 8 %} + {% endif %} .name = "{{sig.name}}", .b1 = {{b1}}, .b2 = {{sig.size}}, @@ -16,6 +20,7 @@ const Signal sigs_{{address}}[] = { .is_signed = {{"true" if sig.is_signed else "false"}}, .factor = {{sig.factor}}, .offset = {{sig.offset}}, + .is_little_endian = {{"true" if sig.is_little_endian else "false"}}, {% if checksum_type == "honda" and sig.name == "CHECKSUM" %} .type = SignalType::HONDA_CHECKSUM, {% elif checksum_type == "honda" and sig.name == "COUNTER" %} @@ -43,12 +48,28 @@ const Msg msgs[] = { {% endfor %} }; +const Val vals[] = { +{% for address, sig in def_vals %} + {% for sg_name, def_val in sig %} + {% set address_hex = "0x%X" % address %} + { + .name = "{{sg_name}}", + .address = {{address_hex}}, + .def_val = {{def_val}}, + .sigs = sigs_{{address}}, + }, + {% endfor %} +{% endfor %} +}; + } const DBC {{dbc.name}} = { .name = "{{dbc.name}}", .num_msgs = ARRAYSIZE(msgs), .msgs = msgs, + .vals = vals, + .num_vals = ARRAYSIZE(vals), }; dbc_init({{dbc.name}}) diff --git a/selfdrive/can/libdbc_py.py b/selfdrive/can/libdbc_py.py index 7a5ae475911b0e..09f5e5121dcc1f 100644 --- a/selfdrive/can/libdbc_py.py +++ b/selfdrive/can/libdbc_py.py @@ -1,52 +1,92 @@ import os -import sys import subprocess from cffi import FFI can_dir = os.path.dirname(os.path.abspath(__file__)) libdbc_fn = os.path.join(can_dir, "libdbc.so") -subprocess.check_call(["make"], stdout=sys.stderr, cwd=can_dir) +subprocess.check_call(["make"], cwd=can_dir) ffi = FFI() ffi.cdef(""" -typedef struct SignalParseOptions { +typedef struct { + const char* name; + double value; +} SignalPackValue; + +typedef struct { uint32_t address; const char* name; double default_value; } SignalParseOptions; -typedef struct MessageParseOptions { +typedef struct { uint32_t address; int check_frequency; } MessageParseOptions; -typedef struct SignalValue { +typedef struct { uint32_t address; uint16_t ts; const char* name; double value; } SignalValue; + +typedef enum { + DEFAULT, + HONDA_CHECKSUM, + HONDA_COUNTER, + TOYOTA_CHECKSUM, +} SignalType; + +typedef struct { + const char* name; + int b1, b2, bo; + bool is_signed; + double factor, offset; + SignalType type; +} Signal; + +typedef struct { + const char* name; + uint32_t address; + unsigned int size; + size_t num_sigs; + const Signal *sigs; +} Msg; + +typedef struct { + const char* name; + uint32_t address; + const char* def_val; + const Signal *sigs; +} Val; + +typedef struct { + const char* name; + size_t num_msgs; + const Msg *msgs; + const Val *vals; + size_t num_vals; +} DBC; + + void* can_init(int bus, const char* dbc_name, size_t num_message_options, const MessageParseOptions* message_options, - size_t num_signal_options, const SignalParseOptions* signal_options); + size_t num_signal_options, const SignalParseOptions* signal_options, bool sendcan, + const char* tcp_addr); void can_update(void* can, uint64_t sec, bool wait); size_t can_query(void* can, uint64_t sec, bool *out_can_valid, size_t out_values_size, SignalValue* out_values); - -typedef struct SignalPackValue { - const char* name; - double value; -} SignalPackValue; +const DBC* dbc_lookup(const char* dbc_name); void* canpack_init(const char* dbc_name); -uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals); - +uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals, int counter); """) libdbc = ffi.dlopen(libdbc_fn) diff --git a/selfdrive/can/packer.cc b/selfdrive/can/packer.cc index 3eddc6aeef79a3..986de6b1172154 100644 --- a/selfdrive/can/packer.cc +++ b/selfdrive/can/packer.cc @@ -1,10 +1,10 @@ #include - #include #include #include #include #include +#include #include "common.h" @@ -12,70 +12,121 @@ namespace { -class CANPacker { -public: - CANPacker(const std::string& dbc_name) { - dbc = dbc_lookup(dbc_name); - assert(dbc); - - for (int i=0; inum_msgs; i++) { - const Msg* msg = &dbc->msgs[i]; - for (int j=0; jnum_sigs; j++) { - const Signal* sig = &msg->sigs[j]; - signal_lookup[std::make_pair(msg->address, std::string(sig->name))] = *sig; - } + // this is the same as read_u64_le, but uses uint64_t as in/out + uint64_t ReverseBytes(uint64_t x) { + return ((x & 0xff00000000000000ull) >> 56) | + ((x & 0x00ff000000000000ull) >> 40) | + ((x & 0x0000ff0000000000ull) >> 24) | + ((x & 0x000000ff00000000ull) >> 8) | + ((x & 0x00000000ff000000ull) << 8) | + ((x & 0x0000000000ff0000ull) << 24) | + ((x & 0x000000000000ff00ull) << 40) | + ((x & 0x00000000000000ffull) << 56); + } + + uint64_t set_value(uint64_t ret, Signal sig, int64_t ival){ + int shift = sig.is_little_endian? sig.b1 : sig.bo; + uint64_t mask = ((1ULL << sig.b2)-1) << shift; + uint64_t dat = (ival & ((1ULL << sig.b2)-1)) << shift; + if (sig.is_little_endian) { + dat = ReverseBytes(dat); + mask = ReverseBytes(mask); } + ret &= ~mask; + ret |= dat; + return ret; } - uint64_t pack(uint32_t address, const std::vector &signals) { - uint64_t ret = 0; - for (const auto& sigval : signals) { - std::string name = std::string(sigval.name); - double value = sigval.value; + class CANPacker { + public: + CANPacker(const std::string& dbc_name) { + dbc = dbc_lookup(dbc_name); + assert(dbc); + + for (int i=0; inum_msgs; i++) { + const Msg* msg = &dbc->msgs[i]; + message_lookup[msg->address] = *msg; + for (int j=0; jnum_sigs; j++) { + const Signal* sig = &msg->sigs[j]; + signal_lookup[std::make_pair(msg->address, std::string(sig->name))] = *sig; + } + } + } - auto sig_it = signal_lookup.find(make_pair(address, name)); - if (sig_it == signal_lookup.end()) { - WARN("undefined signal %s", name.c_str()); - continue; + uint64_t pack(uint32_t address, const std::vector &signals, int counter) { + uint64_t ret = 0; + for (const auto& sigval : signals) { + std::string name = std::string(sigval.name); + double value = sigval.value; + + auto sig_it = signal_lookup.find(std::make_pair(address, name)); + if (sig_it == signal_lookup.end()) { + WARN("undefined signal %s - %d\n", name.c_str(), address); + continue; + } + auto sig = sig_it->second; + + int64_t ival = (int64_t)(round((value - sig.offset) / sig.factor)); + if (ival < 0) { + ival = (1ULL << sig.b2) + ival; + } + + ret = set_value(ret, sig, ival); } - auto sig = sig_it->second; - int64_t ival = (int64_t)((value - sig.offset) / sig.factor); - if (ival < 0) { - WARN("signed pack unsupported right now"); - continue; + if (counter >= 0){ + auto sig_it = signal_lookup.find(std::make_pair(address, "COUNTER")); + if (sig_it == signal_lookup.end()) { + WARN("COUNTER not defined\n"); + return ret; + } + auto sig = sig_it->second; + + if (sig.type != SignalType::HONDA_COUNTER){ + WARN("COUNTER signal type not valid\n"); + } + + ret = set_value(ret, sig, counter); } - uint64_t mask = ((1ULL << sig.b2)-1) << sig.bo; - uint64_t dat = (ival & ((1ULL << sig.b2)-1)) << sig.bo; - ret &= ~mask; - ret |= dat; - } + auto sig_it = signal_lookup.find(std::make_pair(address, "CHECKSUM")); + if (sig_it != signal_lookup.end()) { + auto sig = sig_it->second; + if (sig.type == SignalType::HONDA_CHECKSUM){ + unsigned int chksm = honda_checksum(address, ret, message_lookup[address].size); + ret = set_value(ret, sig, chksm); + } + else if (sig.type == SignalType::TOYOTA_CHECKSUM){ + unsigned int chksm = toyota_checksum(address, ret, message_lookup[address].size); + ret = set_value(ret, sig, chksm); + } else { + WARN("CHECKSUM signal type not valid\n"); + } + } - return ret; - } + return ret; + } -private: - const DBC *dbc = NULL; - std::map, Signal> signal_lookup; -}; + private: + const DBC *dbc = NULL; + std::map, Signal> signal_lookup; + std::map message_lookup; + }; } extern "C" { + void* canpack_init(const char* dbc_name) { + CANPacker *ret = new CANPacker(std::string(dbc_name)); + return (void*)ret; + } -void* canpack_init(const char* dbc_name) { - CANPacker *ret = new CANPacker(std::string(dbc_name)); - return (void*)ret; -} - -uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals) { - CANPacker *cp = (CANPacker*)inst; + uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals, int counter, bool checksum) { + CANPacker *cp = (CANPacker*)inst; - return cp->pack(address, std::vector(vals, vals+num_vals)); -} + return cp->pack(address, std::vector(vals, vals+num_vals), counter); + } } - diff --git a/selfdrive/can/packer.py b/selfdrive/can/packer.py index ff52e165e2f5bd..cc669e60c6a23c 100644 --- a/selfdrive/can/packer.py +++ b/selfdrive/can/packer.py @@ -1,17 +1,26 @@ import struct - from selfdrive.can.libdbc_py import libdbc, ffi + class CANPacker(object): def __init__(self, dbc_name): self.packer = libdbc.canpack_init(dbc_name) + self.dbc = libdbc.dbc_lookup(dbc_name) self.sig_names = {} + self.name_to_address_and_size = {} + + num_msgs = self.dbc[0].num_msgs + for i in range(num_msgs): + msg = self.dbc[0].msgs[i] - def pack(self, addr, values): - # values: [(signal_name, signal_value)] + name = ffi.string(msg.name) + address = msg.address + self.name_to_address_and_size[name] = (address, msg.size) + self.name_to_address_and_size[address] = (address, msg.size) + def pack(self, addr, values, counter): values_thing = [] - for name, value in values: + for name, value in values.iteritems(): if name not in self.sig_names: self.sig_names[name] = ffi.new("char[]", name) @@ -22,16 +31,37 @@ def pack(self, addr, values): values_c = ffi.new("SignalPackValue[]", values_thing) - return libdbc.canpack_pack(self.packer, addr, len(values_thing), values_c) + return libdbc.canpack_pack(self.packer, addr, len(values_thing), values_c, counter) + + def pack_bytes(self, addr, values, counter=-1): + addr, size = self.name_to_address_and_size[addr] + + val = self.pack(addr, values, counter) + r = struct.pack(">Q", val) + return addr, r[:size] - def pack_bytes(self, addr, values): - return struct.pack(">Q", self.pack(addr, values)) + def make_can_msg(self, addr, bus, values, counter=-1): + addr, msg = self.pack_bytes(addr, values, counter) + return [addr, 0, msg, bus] if __name__ == "__main__": - cp = CANPacker("honda_civic_touring_2016_can") - s = cp.pack_bytes(0x30c, [ - ("PCM_SPEED", 123), - ("PCM_GAS", 10), - ]) - print s.encode("hex") + ## little endian test + cp = CANPacker("hyundai_santa_fe_2019_ccan") + s = cp.pack_bytes(0x340, { + "CR_Lkas_StrToqReq": -0.06, + #"CF_Lkas_FcwBasReq": 1, + "CF_Lkas_MsgCount": 7, + "CF_Lkas_HbaSysState": 0, + #"CF_Lkas_Chksum": 3, + }) + s = cp.pack_bytes(0x340, { + "CF_Lkas_MsgCount": 1, + }) + # big endian test + #cp = CANPacker("honda_civic_touring_2016_can_generated") + #s = cp.pack_bytes(0xe4, { + # "STEER_TORQUE": -2, + #}) + print [hex(ord(v)) for v in s[1]] + print(s[1].encode("hex")) diff --git a/selfdrive/can/parser.cc b/selfdrive/can/parser.cc index 828f95a939987b..4a82d9a022f36f 100644 --- a/selfdrive/can/parser.cc +++ b/selfdrive/can/parser.cc @@ -27,19 +27,6 @@ #define MAX_BAD_COUNTER 5 -namespace { - -uint64_t read_u64_be(const uint8_t* v) { - return (((uint64_t)v[0] << 56) - | ((uint64_t)v[1] << 48) - | ((uint64_t)v[2] << 40) - | ((uint64_t)v[3] << 32) - | ((uint64_t)v[4] << 24) - | ((uint64_t)v[5] << 16) - | ((uint64_t)v[6] << 8) - | (uint64_t)v[7]); -} - unsigned int honda_checksum(unsigned int address, uint64_t d, int l) { d >>= ((8-l)*8); // remove padding d >>= 4; // remove checksum @@ -60,10 +47,35 @@ unsigned int toyota_checksum(unsigned int address, uint64_t d, int l) { unsigned int s = l; while (address) { s += address & 0xff; address >>= 8; } while (d) { s += d & 0xff; d >>= 8; } - + return s & 0xFF; } +namespace { + +uint64_t read_u64_be(const uint8_t* v) { + return (((uint64_t)v[0] << 56) + | ((uint64_t)v[1] << 48) + | ((uint64_t)v[2] << 40) + | ((uint64_t)v[3] << 32) + | ((uint64_t)v[4] << 24) + | ((uint64_t)v[5] << 16) + | ((uint64_t)v[6] << 8) + | (uint64_t)v[7]); +} + +uint64_t read_u64_le(const uint8_t* v) { + return ((uint64_t)v[0] + | ((uint64_t)v[1] << 8) + | ((uint64_t)v[2] << 16) + | ((uint64_t)v[3] << 24) + | ((uint64_t)v[4] << 32) + | ((uint64_t)v[5] << 40) + | ((uint64_t)v[6] << 48) + | ((uint64_t)v[7] << 56)); +} + + struct MessageState { uint32_t address; unsigned int size; @@ -81,8 +93,14 @@ struct MessageState { bool parse(uint64_t sec, uint16_t ts_, uint64_t dat) { for (int i=0; i < parse_sigs.size(); i++) { auto& sig = parse_sigs[i]; + int64_t tmp; + + if (sig.is_little_endian){ + tmp = (dat >> sig.b1) & ((1ULL << sig.b2)-1); + } else { + tmp = (dat >> sig.bo) & ((1ULL << sig.b2)-1); + } - int64_t tmp = (dat >> sig.bo) & ((1ULL << sig.b2)-1); if (sig.is_signed) { tmp -= (tmp >> (sig.b2-1)) ? (1ULL << sig.b2) : 0; //signed } @@ -99,7 +117,7 @@ struct MessageState { return false; } } else if (sig.type == SignalType::TOYOTA_CHECKSUM) { - // DEBUG("CHECKSUM %d %d %018llX - %lld vs %d\n", address, size, dat, tmp, toyota_checksum(address, dat, size)); + // INFO("CHECKSUM %d %d %018llX - %lld vs %d\n", address, size, dat, tmp, toyota_checksum(address, dat, size)); if (toyota_checksum(address, dat, size) != tmp) { INFO("%X CHECKSUM FAIL\n", address); @@ -140,13 +158,24 @@ class CANParser { public: CANParser(int abus, const std::string& dbc_name, const std::vector &options, - const std::vector &sigoptions) + const std::vector &sigoptions, + bool sendcan, const std::string& tcp_addr) : bus(abus) { // connect to can on 8006 context = zmq_ctx_new(); subscriber = zmq_socket(context, ZMQ_SUB); zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); - zmq_connect(subscriber, "tcp://127.0.0.1:8006"); + + std::string tcp_addr_str; + + if (sendcan) { + tcp_addr_str = "tcp://" + tcp_addr + ":8017"; + } else { + tcp_addr_str = "tcp://" + tcp_addr + ":8006"; + } + const char *tcp_addr_char = tcp_addr_str.c_str(); + + zmq_connect(subscriber, tcp_addr_char); dbc = dbc_lookup(dbc_name); assert(dbc); @@ -208,6 +237,7 @@ class CANParser { void UpdateCans(uint64_t sec, const capnp::List::Reader& cans) { int msg_count = cans.size(); + uint64_t p; DEBUG("got %d messages\n", msg_count); @@ -228,7 +258,14 @@ class CANParser { uint8_t dat[8] = {0}; memcpy(dat, cmsg.getDat().begin(), cmsg.getDat().size()); - uint64_t p = read_u64_be(dat); + // Assumes all signals in the message are of the same type (little or big endian) + // TODO: allow signals within the same message to have different endianess + auto& sig = message_states[cmsg.getAddress()].parse_sigs[0]; + if (sig.is_little_endian) { + p = read_u64_le(dat); + } else { + p = read_u64_be(dat); + } DEBUG(" proc %X: %llx\n", cmsg.getAddress(), p); @@ -274,7 +311,7 @@ class CANParser { // extract the messages capnp::FlatArrayMessageReader cmsg(amsg); cereal::Event::Reader event = cmsg.getRoot(); - + auto cans = event.getCan(); UpdateCans(sec, cans); @@ -282,6 +319,7 @@ class CANParser { UpdateValid(sec); + zmq_msg_close(&msg); } std::vector query(uint64_t sec) { @@ -290,7 +328,7 @@ class CANParser { for (const auto& kv : message_states) { const auto& state = kv.second; if (sec != 0 && state.seen != sec) continue; - + for (int i=0; i(message_options, message_options+num_message_options) - : std::vector{}), - (signal_options ? std::vector(signal_options, signal_options+num_signal_options) - : std::vector{})); + (message_options ? std::vector(message_options, message_options+num_message_options) + : std::vector{}), + (signal_options ? std::vector(signal_options, signal_options+num_signal_options) + : std::vector{}), sendcan, std::string(tcp_addr)); return (void*)ret; } @@ -376,7 +415,7 @@ int main(int argc, char** argv) { {0x30c, 0}, }, std::vector{ - // sig_name, sig_address, default + // sig_name, sig_address, default {0x158, "XMISSION_SPEED", 0}, {0x1d0, "WHEEL_SPEED_FL", 0}, {0x1d0, "WHEEL_SPEED_FR", 0}, diff --git a/selfdrive/can/parser.py b/selfdrive/can/parser.py index b58abe1be6b838..165673cea5b6e7 100644 --- a/selfdrive/can/parser.py +++ b/selfdrive/can/parser.py @@ -1,15 +1,43 @@ -import os import time from collections import defaultdict +import numbers from selfdrive.can.libdbc_py import libdbc, ffi class CANParser(object): - def __init__(self, dbc_name, signals, checks=[], bus=0): + def __init__(self, dbc_name, signals, checks=[], bus=0, sendcan=False, tcp_addr="127.0.0.1"): self.can_valid = True self.vl = defaultdict(dict) self.ts = defaultdict(dict) + self.dbc_name = dbc_name + self.dbc = libdbc.dbc_lookup(dbc_name) + self.msg_name_to_addres = {} + self.address_to_msg_name = {} + + num_msgs = self.dbc[0].num_msgs + for i in range(num_msgs): + msg = self.dbc[0].msgs[i] + + name = ffi.string(msg.name) + address = msg.address + + self.msg_name_to_addres[name] = address + self.address_to_msg_name[address] = name + + # Convert message names into addresses + for i in range(len(signals)): + s = signals[i] + if not isinstance(s[1], numbers.Number): + s = (s[0], self.msg_name_to_addres[s[1]], s[2]) + signals[i] = s + + for i in range(len(checks)): + c = checks[i] + if not isinstance(c[0], numbers.Number): + c = (self.msg_name_to_addres[c[0]], c[1]) + checks[i] = c + sig_names = dict((name, ffi.new("char[]", name)) for name, _, _ in signals) signal_options_c = ffi.new("SignalParseOptions[]", [ @@ -21,15 +49,15 @@ def __init__(self, dbc_name, signals, checks=[], bus=0): message_options = dict((address, 0) for _, address, _ in signals) message_options.update(dict(checks)) - + message_options_c = ffi.new("MessageParseOptions[]", [ { - 'address': address, + 'address': msg_address, 'check_frequency': freq, - } for address, freq in message_options.iteritems()]) + } for msg_address, freq in message_options.iteritems()]) self.can = libdbc.can_init(bus, dbc_name, len(message_options_c), message_options_c, - len(signal_options_c), signal_options_c) + len(signal_options_c), signal_options_c, sendcan, tcp_addr) self.p_can_valid = ffi.new("bool*") @@ -54,6 +82,10 @@ def update_vl(self, sec): name = ffi.string(cv.name) self.vl[address][name] = cv.value self.ts[address][name] = cv.ts + + sig_name = self.address_to_msg_name[address] + self.vl[sig_name][name] = cv.value + self.ts[sig_name][name] = cv.ts ret.add(address) return ret @@ -61,6 +93,44 @@ def update(self, sec, wait): libdbc.can_update(self.can, sec, wait) return self.update_vl(sec) +class CANDefine(object): + def __init__(self, dbc_name): + self.dv = defaultdict(dict) + self.dbc_name = dbc_name + self.dbc = libdbc.dbc_lookup(dbc_name) + + num_vals = self.dbc[0].num_vals + + self.address_to_msg_name = {} + num_msgs = self.dbc[0].num_msgs + for i in range(num_msgs): + msg = self.dbc[0].msgs[i] + name = ffi.string(msg.name) + address = msg.address + self.address_to_msg_name[address] = name + + for i in range(num_vals): + val = self.dbc[0].vals[i] + + sgname = ffi.string(val.name) + address = val.address + def_val = ffi.string(val.def_val) + + #separate definition/value pairs + def_val = def_val.split() + values = [int(v) for v in def_val[::2]] + defs = def_val[1::2] + + if address not in self.dv: + self.dv[address] = {} + msgname = self.address_to_msg_name[address] + self.dv[msgname] = {} + + # two ways to lookup: address or msg name + self.dv[address][sgname] = {v: d for v, d in zip(values, defs)} #build dict + self.dv[msgname][sgname] = self.dv[address][sgname] + + if __name__ == "__main__": from common.realtime import sec_since_boot @@ -74,7 +144,7 @@ def update(self, sec, wait): # signals = [ - # ("XMISSION_SPEED", 0x158, 0), #sig_name, sig_address, default + # ("XMISSION_SPEED", 0x158, 0), #sig_name, sig_address, default # ("WHEEL_SPEED_FL", 0x1d0, 0), # ("WHEEL_SPEED_FR", 0x1d0, 0), # ("WHEEL_SPEED_RL", 0x1d0, 0), @@ -123,7 +193,7 @@ def update(self, sec, wait): # (0x405, 3), # ] - # cp = CANParser("honda_civic_touring_2016_can", signals, checks, 0) + # cp = CANParser("honda_civic_touring_2016_can_generated", signals, checks, 0) signals = [ @@ -164,13 +234,13 @@ def update(self, sec, wait): (608, 50), ] - cp = CANParser("toyota_rav4_2017_pt", signals, checks, 0) + cp = CANParser("toyota_rav4_2017_pt_generated", signals, checks, 0) # print cp.vl while True: cp.update(int(sec_since_boot()*1e9), True) # print cp.vl - print cp.ts - print cp.can_valid + print(cp.ts) + print(cp.can_valid) time.sleep(0.01) diff --git a/selfdrive/car/honda/old_can_parser.py b/selfdrive/can/plant_can_parser.py similarity index 96% rename from selfdrive/car/honda/old_can_parser.py rename to selfdrive/can/plant_can_parser.py index 6f7f3dce3d6131..44939747cee521 100644 --- a/selfdrive/car/honda/old_can_parser.py +++ b/selfdrive/can/plant_can_parser.py @@ -1,3 +1,4 @@ +### old can parser just used by plant.py for regression tests import os import opendbc from collections import defaultdict @@ -7,7 +8,7 @@ from common.dbc import dbc class CANParser(object): - def __init__(self, dbc_f, signals, checks=[]): + def __init__(self, dbc_f, signals, checks=None): ### input: # dbc_f : dbc file # signals : List of tuples (name, address, ival) where @@ -19,6 +20,7 @@ def __init__(self, dbc_f, signals, checks=[]): # monitored. # - frequency is the frequency at which health should be monitored. + checks = [] if checks is None else checks self.msgs_ck = set([check[0] for check in checks]) self.frqs = dict(checks) self.can_valid = False # start with False CAN assumption diff --git a/selfdrive/can/process_dbc.py b/selfdrive/can/process_dbc.py index c48afc85668b3d..331e0a3130ca8d 100755 --- a/selfdrive/can/process_dbc.py +++ b/selfdrive/can/process_dbc.py @@ -4,7 +4,7 @@ import jinja2 -import opendbc +from collections import Counter from common.dbc import dbc if len(sys.argv) != 3: @@ -24,14 +24,41 @@ msgs = [(address, msg_name, msg_size, sorted(msg_sigs, key=lambda s: s.name not in ("COUNTER", "CHECKSUM"))) # process counter and checksums first for address, ((msg_name, msg_size), msg_sigs) in sorted(can_dbc.msgs.iteritems()) if msg_sigs] +def_vals = {a: set(b) for a,b in can_dbc.def_vals.items()} #remove duplicates +def_vals = [(address, sig) for address, sig in sorted(def_vals.iteritems())] + if can_dbc.name.startswith("honda") or can_dbc.name.startswith("acura"): checksum_type = "honda" -elif can_dbc.name.startswith("toyota"): + checksum_size = 4 +elif can_dbc.name.startswith("toyota") or can_dbc.name.startswith("lexus"): checksum_type = "toyota" + checksum_size = 8 else: checksum_type = None -parser_code = template.render(dbc=can_dbc, checksum_type=checksum_type, msgs=msgs, len=len) +for address, msg_name, msg_size, sigs in msgs: + for sig in sigs: + if checksum_type is not None and sig.name == "CHECKSUM": + if sig.size != checksum_size: + sys.exit("CHECKSUM is not %d bits longs %s" % (checksum_size, msg_name)) + if checksum_type == "honda" and sig.start_bit % 8 != 3: + sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) + if checksum_type == "toyota" and sig.start_bit % 8 != 7: + sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) + if checksum_type == "honda" and sig.name == "COUNTER": + if sig.size != 2: + sys.exit("COUNTER is not 2 bits longs %s" % msg_name) + if sig.start_bit % 8 != 5: + sys.exit("COUNTER starts at wrong bit %s" % msg_name) + + +# Fail on duplicate message names +c = Counter([msg_name for address, msg_name, msg_size, sigs in msgs]) +for name, count in c.items(): + if count > 1: + sys.exit("Duplicate message name in DBC file %s" % name) + +parser_code = template.render(dbc=can_dbc, checksum_type=checksum_type, msgs=msgs, def_vals=def_vals, len=len) with open(out_fn, "w") as out_f: out_f.write(parser_code) diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 4526d35c405e8c..0473c8874f7cdc 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -1,94 +1,26 @@ -import os -from cereal import car +# functions common among cars +from common.numpy_fast import clip -from common.realtime import sec_since_boot -from common.fingerprints import eliminate_incompatible_cars, all_known_cars -from selfdrive.swaglog import cloudlog -import selfdrive.messaging as messaging -from selfdrive.car.honda.interface import CarInterface as HondaInterface -from selfdrive.car.toyota.interface import CarInterface as ToyotaInterface -from selfdrive.car.mock.interface import CarInterface as MockInterface +def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None): + return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc} -try: - from .simulator.interface import CarInterface as SimInterface -except ImportError: - SimInterface = None -try: - from .simulator2.interface import CarInterface as Sim2Interface -except ImportError: - Sim2Interface = None +def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): + # limits due to driver torque + driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + driver_min_torque = -LIMITS.STEER_MAX + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + max_steer_allowed = max(min(LIMITS.STEER_MAX, driver_max_torque), 0) + min_steer_allowed = min(max(-LIMITS.STEER_MAX, driver_min_torque), 0) + apply_torque = clip(apply_torque, min_steer_allowed, max_steer_allowed) -interfaces = { - "HONDA CIVIC 2016 TOURING": HondaInterface, - "ACURA ILX 2016 ACURAWATCH PLUS": HondaInterface, - "HONDA ACCORD 2016 TOURING": HondaInterface, - "HONDA CR-V 2016 TOURING": HondaInterface, - "TOYOTA PRIUS 2017": ToyotaInterface, - "TOYOTA RAV4 2017": ToyotaInterface, - "TOYOTA RAV4 2017 HYBRID": ToyotaInterface, + # slow rate if steer torque increases in magnitude + if apply_torque_last > 0: + apply_torque = clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), + apply_torque_last + LIMITS.STEER_DELTA_UP) + else: + apply_torque = clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP, + min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) - "simulator": SimInterface, - "simulator2": Sim2Interface, - - "mock": MockInterface -} - -# **** for use live only **** -def fingerprint(logcan, timeout): - if os.getenv("SIMULATOR") is not None or logcan is None: - return ("simulator", None) - elif os.getenv("SIMULATOR2") is not None: - return ("simulator2", None) - - finger_st = sec_since_boot() - - cloudlog.warning("waiting for fingerprint...") - candidate_cars = all_known_cars() - finger = {} - st = None - while 1: - for a in messaging.drain_sock(logcan, wait_for_one=True): - if st is None: - st = sec_since_boot() - for can in a.can: - if can.src == 0: - finger[can.address] = len(can.dat) - candidate_cars = eliminate_incompatible_cars(can, candidate_cars) - - ts = sec_since_boot() - # if we only have one car choice and the time_fingerprint since we got our first - # message has elapsed, exit. Toyota needs higher time_fingerprint, since DSU does not - # broadcast immediately - if len(candidate_cars) == 1 and st is not None: - time_fingerprint = 1.0 if "TOYOTA" in candidate_cars[0] else 0.1 - if (ts-st) > time_fingerprint: - break - - # bail if no cars left or we've been waiting too long - elif len(candidate_cars) == 0 or (timeout and ts-finger_st > timeout): - return None, finger - - cloudlog.warning("fingerprinted %s", candidate_cars[0]) - return (candidate_cars[0], finger) - - -def get_car(logcan, sendcan=None, passive=True): - - # TODO: timeout only useful for replays so controlsd can start before unlogger - timeout = 1. if passive else None - candidate, fingerprints = fingerprint(logcan, timeout) - - if candidate is None: - cloudlog.warning("car doesn't match any fingerprints: %r", fingerprints) - if passive: - candidate = "mock" - else: - return None, None - - interface_cls = interfaces[candidate] - params = interface_cls.get_params(candidate, fingerprints) - - return interface_cls(params, sendcan), params + return int(round(apply_torque)) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py new file mode 100644 index 00000000000000..dbc392cb23e584 --- /dev/null +++ b/selfdrive/car/car_helpers.py @@ -0,0 +1,107 @@ +import os +import time +from common.basedir import BASEDIR +from common.realtime import sec_since_boot +from common.fingerprints import eliminate_incompatible_cars, all_known_cars +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging + +def load_interfaces(x): + ret = {} + for interface in x: + try: + imp = __import__('selfdrive.car.%s.interface' % interface, fromlist=['CarInterface']).CarInterface + except ImportError: + imp = None + for car in x[interface]: + ret[car] = imp + return ret + + +def _get_interface_names(): + # read all the folders in selfdrive/car and return a dict where: + # - keys are all the car names that which we have an interface for + # - values are lists of spefic car models for a given car + interface_names = {} + for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: + try: + car_name = car_folder.split('/')[-1] + model_names = __import__('selfdrive.car.%s.values' % car_name, fromlist=['CAR']).CAR + model_names = [getattr(model_names, c) for c in model_names.__dict__.keys() if not c.startswith("__")] + interface_names[car_name] = model_names + except (ImportError, IOError): + pass + + return interface_names + + +# imports from directory selfdrive/car// +interfaces = load_interfaces(_get_interface_names()) + + +# **** for use live only **** +def fingerprint(logcan, timeout): + if os.getenv("SIMULATOR2") is not None: + return ("simulator2", None) + elif os.getenv("SIMULATOR") is not None: + return ("simulator", None) + + cloudlog.warning("waiting for fingerprint...") + candidate_cars = all_known_cars() + finger = {} + st = None + st_passive = sec_since_boot() # only relevant when passive + can_seen = False + while 1: + for a in messaging.drain_sock(logcan): + for can in a.can: + can_seen = True + # ignore everything not on bus 0 and with more than 11 bits, + # which are ussually sporadic and hard to include in fingerprints + if can.src == 0 and can.address < 0x800: + finger[can.address] = len(can.dat) + candidate_cars = eliminate_incompatible_cars(can, candidate_cars) + + if st is None and can_seen: + st = sec_since_boot() # start time + ts = sec_since_boot() + # if we only have one car choice and the time_fingerprint since we got our first + # message has elapsed, exit. Toyota needs higher time_fingerprint, since DSU does not + # broadcast immediately + if len(candidate_cars) == 1 and st is not None: + # TODO: better way to decide to wait more if Toyota + time_fingerprint = 1.0 if ("TOYOTA" in candidate_cars[0] or "LEXUS" in candidate_cars[0]) else 0.1 + if (ts-st) > time_fingerprint: + break + + # bail if no cars left or we've been waiting too long + elif len(candidate_cars) == 0 or (timeout and (ts - st_passive) > timeout): + return None, finger + + time.sleep(0.01) + + cloudlog.warning("fingerprinted %s", candidate_cars[0]) + return (candidate_cars[0], finger) + + +def get_car(logcan, sendcan=None, passive=True): + # TODO: timeout only useful for replays so controlsd can start before unlogger + timeout = 2. if passive else None + candidate, fingerprints = fingerprint(logcan, timeout) + + if candidate is None: + cloudlog.warning("car doesn't match any fingerprints: %r", fingerprints) + if passive: + candidate = "mock" + else: + return None, None + + interface_cls = interfaces[candidate] + + if interface_cls is None: + cloudlog.warning("car matched %s, but interface wasn't available or failed to import" % candidate) + return None, None + + params = interface_cls.get_params(candidate, fingerprints) + + return interface_cls(params, sendcan), params diff --git a/selfdrive/radar/toyota/__init__.py b/selfdrive/car/ford/__init__.py similarity index 100% rename from selfdrive/radar/toyota/__init__.py rename to selfdrive/car/ford/__init__.py diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py new file mode 100644 index 00000000000000..c860cfdee4e353 --- /dev/null +++ b/selfdrive/car/ford/carstate.py @@ -0,0 +1,90 @@ +from selfdrive.can.parser import CANParser +from selfdrive.config import Conversions as CV +from selfdrive.car.ford.values import DBC +from common.kalman.simple_kalman import KF1D +import numpy as np + +WHEEL_RADIUS = 0.33 + +def get_can_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("WhlRr_W_Meas", "WheelSpeed_CG1", 0.), + ("WhlRl_W_Meas", "WheelSpeed_CG1", 0.), + ("WhlFr_W_Meas", "WheelSpeed_CG1", 0.), + ("WhlFl_W_Meas", "WheelSpeed_CG1", 0.), + ("SteWhlRelInit_An_Sns", "Steering_Wheel_Data_CG1", 0.), + ("Cruise_State", "Cruise_Status", 0.), + ("Set_Speed", "Cruise_Status", 0.), + ("LaActAvail_D_Actl", "Lane_Keep_Assist_Status", 0), + ("LaHandsOff_B_Actl", "Lane_Keep_Assist_Status", 0), + ("LaActDeny_B_Actl", "Lane_Keep_Assist_Status", 0), + ("ApedPosScal_Pc_Actl", "EngineData_14", 0.), + ("Dist_Incr", "Steering_Buttons", 0.), + ("Brake_Drv_Appl", "Cruise_Status", 0.), + ("Brake_Lights", "BCM_to_HS_Body", 0.), + ] + + checks = [ + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + + +class CarState(object): + def __init__(self, CP): + + self.CP = CP + self.left_blinker_on = 0 + self.right_blinker_on = 0 + + # initialize can parser + self.car_fingerprint = CP.carFingerprint + + # vEgo kalman filter + dt = 0.01 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0.0 + + def update(self, cp): + # copy can_valid + self.can_valid = cp.can_valid + + # update prevs, update must run once per loop + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + + # calc best v_ego estimate, by averaging two opposite corners + self.v_wheel_fl = cp.vl["WheelSpeed_CG1"]['WhlRr_W_Meas'] * WHEEL_RADIUS + self.v_wheel_fr = cp.vl["WheelSpeed_CG1"]['WhlRl_W_Meas'] * WHEEL_RADIUS + self.v_wheel_rl = cp.vl["WheelSpeed_CG1"]['WhlFr_W_Meas'] * WHEEL_RADIUS + self.v_wheel_rr = cp.vl["WheelSpeed_CG1"]['WhlFl_W_Meas'] * WHEEL_RADIUS + self.v_wheel = float(np.mean([self.v_wheel_fl, self.v_wheel_fr, self.v_wheel_rl, self.v_wheel_rr])) + + # Kalman filter + if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) + + self.v_ego_raw = self.v_wheel + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + self.standstill = not self.v_wheel > 0.001 + + self.angle_steers = cp.vl["Steering_Wheel_Data_CG1"]['SteWhlRelInit_An_Sns'] + self.v_cruise_pcm = cp.vl["Cruise_Status"]['Set_Speed'] * CV.MPH_TO_MS + self.pcm_acc_status = cp.vl["Cruise_Status"]['Cruise_State'] + self.main_on = cp.vl["Cruise_Status"]['Cruise_State'] != 0 + self.lkas_state = cp.vl["Lane_Keep_Assist_Status"]['LaActAvail_D_Actl'] + self.steer_override = not cp.vl["Lane_Keep_Assist_Status"]['LaHandsOff_B_Actl'] + self.steer_error = cp.vl["Lane_Keep_Assist_Status"]['LaActDeny_B_Actl'] + self.user_gas = cp.vl["EngineData_14"]['ApedPosScal_Pc_Actl'] + self.brake_pressed = bool(cp.vl["Cruise_Status"]["Brake_Drv_Appl"]) + self.brake_lights = bool(cp.vl["BCM_to_HS_Body"]["Brake_Lights"]) + self.generic_toggle = bool(cp.vl["Steering_Buttons"]["Dist_Incr"]) diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py new file mode 100755 index 00000000000000..1f0e36e0dc23ef --- /dev/null +++ b/selfdrive/car/ford/interface.py @@ -0,0 +1,218 @@ +#!/usr/bin/env python +from common.realtime import sec_since_boot +from cereal import car, log +from selfdrive.swaglog import cloudlog +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.ford.carstate import CarState, get_can_parser +from selfdrive.car.ford.fordcan import MAX_ANGLE + +try: + from selfdrive.car.ford.carcontroller import CarController +except ImportError: + CarController = None + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + self.VM = VehicleModel(CP) + + self.frame = 0 + self.can_invalid_count = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.cruise_enabled_prev = False + + # *** init the major players *** + self.CS = CarState(CP) + + self.cp = get_can_parser(CP) + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(self.cp.dbc_name, CP.enableCamera, self.VM) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 3.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 + + ret = car.CarParams.new_message() + + ret.carName = "ford" + ret.carFingerprint = candidate + + ret.safetyModel = car.CarParams.SafetyModels.ford + + # pedal + ret.enableCruise = True + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923. * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 85400 + tireStiffnessRear_civic = 90000 + + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.wheelbase = 2.85 + ret.steerRatio = 14.8 + ret.mass = 3045. * CV.LB_TO_KG + std_cargo + ret.steerKpV, ret.steerKiV = [[0.01], [0.005]] # TODO: tune this + ret.steerKf = 1. / MAX_ANGLE # MAX Steer angle to normalize FF + ret.steerActuatorDelay = 0.1 # Default delay, not measured yet + ret.steerRateCost = 1.0 + + f = 1.2 + tireStiffnessFront_civic *= f + tireStiffnessRear_civic *= f + + ret.centerToFront = ret.wheelbase * 0.44 + + ret.longPidDeadzoneBP = [0., 9.] + ret.longPidDeadzoneV = [0., .15] + + # 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. + ret.minEnableSpeed = -1. + + centerToRear = ret.wheelbase - ret.centerToFront + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = tireStiffnessFront_civic * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = tireStiffnessRear_civic * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + # no rear steering, at least on the listed cars above + ret.steerRatioRear = 0. + ret.steerControlType = car.CarParams.SteerControlType.angle + + # steer, gas, brake limitations VS speed + ret.steerMaxBP = [0.] # breakpoints at 1 and 40 kph + ret.steerMaxV = [1.0] # 2/3rd torque allowed above 45 kph + ret.gasMaxBP = [0.] + ret.gasMaxV = [0.5] + ret.brakeMaxBP = [5., 20.] + ret.brakeMaxV = [1., 0.8] + + ret.enableCamera = not any(x for x in [970, 973, 984] if x in fingerprint) + cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera) + + ret.steerLimitAlert = False + ret.stoppingControl = False + ret.startAccel = 0.0 + + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [3.6, 2.4, 1.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.54, 0.36] + + return ret + + # returns a car.CarState + def update(self, c): + # ******************* do can recv ******************* + canMonoTimes = [] + + self.cp.update(int(sec_since_boot() * 1e9), False) + + self.CS.update(self.cp) + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.CS.v_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + ret.steeringPressed = self.CS.steer_override + + # gas pedal + ret.gas = self.CS.user_gas / 100. + ret.gasPressed = self.CS.user_gas > 0.0001 + ret.brakePressed = self.CS.brake_pressed + ret.brakeLights = self.CS.brake_lights + + ret.cruiseState.enabled = not (self.CS.pcm_acc_status in [0, 3]) + ret.cruiseState.speed = self.CS.v_cruise_pcm + ret.cruiseState.available = self.CS.pcm_acc_status != 0 + + ret.genericToggle = self.CS.generic_toggle + + # events + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + + if self.CS.steer_error: + events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + + # enable request in prius is simple, as we activate when Toyota is active (rising edge) + if ret.cruiseState.enabled and not self.cruise_enabled_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + elif not ret.cruiseState.enabled: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed and (not self.brake_pressed_prev or ret.vEgo > 0.001)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + + if self.CS.lkas_state not in [2, 3] and ret.vEgo > 13.* CV.MPH_TO_MS and ret.cruiseState.enabled: + events.append(create_event('steerTempUnavailableMute', [ET.WARNING])) + + ret.events = events + ret.canMonoTimes = canMonoTimes + + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + self.cruise_enabled_prev = ret.cruiseState.enabled + + return ret.as_reader() + + # pass in a car.CarControl + # to be called @ 100hz + def apply(self, c, perception_state=log.Live20Data.new_message()): + + self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators, + c.hudControl.visualAlert, c.cruiseControl.cancel) + + self.frame += 1 + return False diff --git a/selfdrive/radar/toyota/interface.py b/selfdrive/car/ford/radar_interface.py similarity index 66% rename from selfdrive/radar/toyota/interface.py rename to selfdrive/car/ford/radar_interface.py index cd60925d0b8431..2acea9d7084949 100755 --- a/selfdrive/radar/toyota/interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -9,22 +9,20 @@ import selfdrive.messaging as messaging -RADAR_MSGS = range(0x210, 0x220) +RADAR_MSGS = range(0x500, 0x540) def _create_radard_can_parser(): - dbc_f = 'toyota_prius_2017_adas.dbc' + dbc_f = 'ford_fusion_2018_adas.dbc' msg_n = len(RADAR_MSGS) - msg_last = RADAR_MSGS[-1] - signals = zip(['LONG_DIST'] * msg_n + ['NEW_TRACK'] * msg_n + ['LAT_DIST'] * msg_n + - ['REL_SPEED'] * msg_n + ['VALID'] * msg_n, - RADAR_MSGS * 5, - [255] * msg_n + [1] * msg_n + [0] * msg_n + [0] * msg_n + [0] * msg_n) + signals = zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, + RADAR_MSGS * 3, + [0] * msg_n + [0] * msg_n + [0] * msg_n) checks = zip(RADAR_MSGS, [20]*msg_n) return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) class RadarInterface(object): - def __init__(self): + def __init__(self, CP): # radar self.pts = {} self.validCnt = {key: 0 for key in RADAR_MSGS} @@ -45,8 +43,8 @@ def update(self): while 1: tm = int(sec_since_boot() * 1e9) updated_messages.update(self.rcp.update(tm, True)) - # TODO: use msg_last - if 0x21f in updated_messages: + # TODO: do not hardcode last msg + if 0x53f in updated_messages: break ret = car.RadarState.new_message() @@ -59,27 +57,27 @@ def update(self): for ii in updated_messages: cpt = self.rcp.vl[ii] - if cpt['LONG_DIST'] >=255 or cpt['NEW_TRACK']: + if cpt['X_Rel'] > 0.00001: self.validCnt[ii] = 0 # reset counter - if cpt['VALID'] and cpt['LONG_DIST'] < 255: + if cpt['X_Rel'] > 0.00001: self.validCnt[ii] += 1 else: self.validCnt[ii] = max(self.validCnt[ii] -1, 0) - #print ii, self.validCnt[ii], cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] + #print ii, self.validCnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] # radar point only valid if there have been enough valid measurements if self.validCnt[ii] > 0: - if ii not in self.pts or cpt['NEW_TRACK']: + if ii not in self.pts: self.pts[ii] = car.RadarState.RadarPoint.new_message() self.pts[ii].trackId = self.track_id self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].dRel = cpt['X_Rel'] # from front of car + self.pts[ii].yRel = cpt['X_Rel'] * cpt['Angle'] * np.pi / 180. # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['V_Rel'] self.pts[ii].aRel = float('nan') self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = bool(cpt['VALID']) + self.pts[ii].measured = True else: if ii in self.pts: del self.pts[ii] @@ -88,7 +86,7 @@ def update(self): return ret if __name__ == "__main__": - RI = RadarInterface() + RI = RadarInterface(None) while 1: ret = RI.update() print(chr(27) + "[2J") diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py new file mode 100644 index 00000000000000..b8890107fcc52b --- /dev/null +++ b/selfdrive/car/ford/values.py @@ -0,0 +1,14 @@ +from selfdrive.car import dbc_dict + +class CAR: + FUSION = "FORD FUSION 2018" + +FINGERPRINTS = { + CAR.FUSION: [{ + 71: 8, 74: 8, 75: 8, 76: 8, 90: 8, 92: 8, 93: 8, 118: 8, 119: 8, 120: 8, 125: 8, 129: 8, 130: 8, 131: 8, 132: 8, 133: 8, 145: 8, 146: 8, 357: 8, 359: 8, 360: 8, 361: 8, 376: 8, 390: 8, 391: 8, 392: 8, 394: 8, 512: 8, 514: 8, 516: 8, 531: 8, 532: 8, 534: 8, 535: 8, 560: 8, 578: 8, 604: 8, 613: 8, 673: 8, 827: 8, 848: 8, 934: 8, 935: 8, 936: 8, 947: 8, 963: 8, 970: 8, 972: 8, 973: 8, 984: 8, 992: 8, 994: 8, 997: 8, 998: 8, 1003: 8, 1034: 8, 1045: 8, 1046: 8, 1053: 8, 1054: 8, 1058: 8, 1059: 8, 1068: 8, 1072: 8, 1073: 8, 1082: 8, 1107: 8, 1108: 8, 1109: 8, 1110: 8, 1200: 8, 1427: 8, 1430: 8, 1438: 8, 1459: 8 + }], +} + +DBC = { + CAR.FUSION: dbc_dict('ford_fusion_2018_pt', 'ford_fusion_2018_adas'), +} diff --git a/selfdrive/car/gm/__init__.py b/selfdrive/car/gm/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py new file mode 100644 index 00000000000000..3518e98c5a663a --- /dev/null +++ b/selfdrive/car/gm/carcontroller.py @@ -0,0 +1,196 @@ +from common.numpy_fast import interp +from common.realtime import sec_since_boot +from selfdrive.config import Conversions as CV +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car.gm import gmcan +from selfdrive.car.gm.values import CAR, DBC +from selfdrive.can.packer import CANPacker + + +class CarControllerParams(): + def __init__(self, car_fingerprint): + if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + self.STEER_MAX = 300 + self.STEER_STEP = 2 # how often we update the steer cmd + self.STEER_DELTA_UP = 7 # ~0.75s time to peak torque (255/50hz/0.75s) + self.STEER_DELTA_DOWN = 17 # ~0.3s from peak torque to zero + elif car_fingerprint == CAR.CADILLAC_CT6: + self.STEER_MAX = 150 + self.STEER_STEP = 1 # how often we update the steer cmd + self.STEER_DELTA_UP = 2 # 0.75s time to peak torque + self.STEER_DELTA_DOWN = 5 # 0.3s from peak torque to zero + + self.STEER_DRIVER_ALLOWANCE = 50 # allowed driver torque before start limiting + self.STEER_DRIVER_MULTIPLIER = 4 # weight driver torque heavily + self.STEER_DRIVER_FACTOR = 100 # from dbc + self.NEAR_STOP_BRAKE_PHASE = 0.5 # m/s, more aggressive braking near full stop + + # Takes case of "Service Adaptive Cruise" and "Service Front Camera" + # dashboard messages. + self.ADAS_KEEPALIVE_STEP = 100 + self.CAMERA_KEEPALIVE_STEP = 100 + + # pedal lookups, only for Volt + MAX_GAS = 3072 # Only a safety limit + ZERO_GAS = 2048 + MAX_BRAKE = 350 # Should be around 3.5m/s^2, including regen + self.MAX_ACC_REGEN = 1404 # ACC Regen braking is slightly less powerful than max regen paddle + self.GAS_LOOKUP_BP = [-0.25, 0., 0.5] + self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, ZERO_GAS, MAX_GAS] + self.BRAKE_LOOKUP_BP = [-1., -0.25] + self.BRAKE_LOOKUP_V = [MAX_BRAKE, 0] + + +def actuator_hystereses(final_pedal, pedal_steady): + # hyst params... TODO: move these to VehicleParams + pedal_hyst_gap = 0.01 # don't change pedal command for small oscilalitons within this value + + # for small pedal oscillations within pedal_hyst_gap, don't change the pedal command + if final_pedal == 0.: + pedal_steady = 0. + elif final_pedal > pedal_steady + pedal_hyst_gap: + pedal_steady = final_pedal - pedal_hyst_gap + elif final_pedal < pedal_steady - pedal_hyst_gap: + pedal_steady = final_pedal + pedal_hyst_gap + final_pedal = pedal_steady + + return final_pedal, pedal_steady + + +class CarController(object): + def __init__(self, canbus, car_fingerprint, allow_controls): + self.pedal_steady = 0. + self.start_time = sec_since_boot() + self.chime = 0 + self.steer_idx = 0 + self.apply_steer_last = 0 + self.car_fingerprint = car_fingerprint + self.allow_controls = allow_controls + self.lka_icon_status_last = (False, False) + + # Setup detection helper. Routes commands to + # an appropriate CAN bus number. + self.canbus = canbus + self.params = CarControllerParams(car_fingerprint) + + self.packer_pt = CANPacker(DBC[car_fingerprint]['pt']) + self.packer_ch = CANPacker(DBC[car_fingerprint]['chassis']) + + def update(self, sendcan, enabled, CS, frame, actuators, \ + hud_v_cruise, hud_show_lanes, hud_show_car, chime, chime_cnt): + """ Controls thread """ + + # Sanity check. + if not self.allow_controls: + return + + P = self.params + + # Send CAN commands. + can_sends = [] + canbus = self.canbus + + ### STEER ### + + if (frame % P.STEER_STEP) == 0: + lkas_enabled = enabled and not CS.steer_not_allowed and CS.v_ego > 3. + if lkas_enabled: + apply_steer = actuators.steer * P.STEER_MAX + apply_steer = apply_std_steer_torque_limits(apply_steer, self.apply_steer_last, CS.steer_torque_driver, P) + else: + apply_steer = 0 + + self.apply_steer_last = apply_steer + idx = (frame / P.STEER_STEP) % 4 + + if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + can_sends.append(gmcan.create_steering_control(self.packer_pt, + canbus.powertrain, apply_steer, idx, lkas_enabled)) + if self.car_fingerprint == CAR.CADILLAC_CT6: + can_sends += gmcan.create_steering_control_ct6(self.packer_pt, + canbus, apply_steer, CS.v_ego, idx, lkas_enabled) + + ### GAS/BRAKE ### + + if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + # no output if not enabled, but keep sending keepalive messages + # treat pedals as one + final_pedal = actuators.gas - actuators.brake + + # *** apply pedal hysteresis *** + final_brake, self.brake_steady = actuator_hystereses( + final_pedal, self.pedal_steady) + + if not enabled: + # Stock ECU sends max regen when not enabled. + apply_gas = P.MAX_ACC_REGEN + apply_brake = 0 + else: + apply_gas = int(round(interp(final_pedal, P.GAS_LOOKUP_BP, P.GAS_LOOKUP_V))) + apply_brake = int(round(interp(final_pedal, P.BRAKE_LOOKUP_BP, P.BRAKE_LOOKUP_V))) + + # Gas/regen and brakes - all at 25Hz + if (frame % 4) == 0: + idx = (frame / 4) % 4 + + at_full_stop = enabled and CS.standstill + near_stop = enabled and (CS.v_ego < P.NEAR_STOP_BRAKE_PHASE) + can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, canbus.chassis, apply_brake, idx, near_stop, at_full_stop)) + + at_full_stop = enabled and CS.standstill + can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, canbus.powertrain, apply_gas, idx, enabled, at_full_stop)) + + # Send dashboard UI commands (ACC status), 25hz + if (frame % 4) == 0: + can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, canbus.powertrain, enabled, hud_v_cruise * CV.MS_TO_KPH, hud_show_car)) + + # Radar needs to know current speed and yaw rate (50hz), + # and that ADAS is alive (10hz) + time_and_headlights_step = 10 + tt = sec_since_boot() + + if frame % time_and_headlights_step == 0: + idx = (frame / time_and_headlights_step) % 4 + can_sends.append(gmcan.create_adas_time_status(canbus.obstacle, int((tt - self.start_time) * 60), idx)) + can_sends.append(gmcan.create_adas_headlights_status(canbus.obstacle)) + + speed_and_accelerometer_step = 2 + if frame % speed_and_accelerometer_step == 0: + idx = (frame / speed_and_accelerometer_step) % 4 + can_sends.append(gmcan.create_adas_steering_status(canbus.obstacle, idx)) + can_sends.append(gmcan.create_adas_accelerometer_speed_status(canbus.obstacle, CS.v_ego, idx)) + + if frame % P.ADAS_KEEPALIVE_STEP == 0: + can_sends += gmcan.create_adas_keepalive(canbus.powertrain) + + # Show green icon when LKA torque is applied, and + # alarming orange icon when approaching torque limit. + # If not sent again, LKA icon disappears in about 5 seconds. + # Conveniently, sending camera message periodically also works as a keepalive. + lka_active = CS.lkas_status == 1 + 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: + can_sends.append(gmcan.create_lka_icon_command(canbus.sw_gmlan, lka_active, lka_critical)) + self.lka_icon_status_last = lka_icon_status + + # Send chimes + if self.chime != chime: + duration = 0x3c + + # There is no 'repeat forever' chime command + # TODO: Manage periodic re-issuing of chime command + # and chime cancellation + if chime_cnt == -1: + chime_cnt = 10 + + if chime != 0: + can_sends.append(gmcan.create_chime_command(canbus.sw_gmlan, chime, duration, chime_cnt)) + + # If canceling a repeated chime, cancel command must be + # issued for the same chime type and duration + self.chime = chime + + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py new file mode 100644 index 00000000000000..ab0dc79d186b2a --- /dev/null +++ b/selfdrive/car/gm/carstate.py @@ -0,0 +1,149 @@ +import numpy as np +from cereal import car +from common.kalman.simple_kalman import KF1D +from selfdrive.config import Conversions as CV +from selfdrive.can.parser import CANParser +from selfdrive.car.gm.values import DBC, CAR, parse_gear_shifter, \ + CruiseButtons, is_eps_status_ok, \ + STEER_THRESHOLD + +def get_powertrain_can_parser(CP, canbus): + # this function generates lists for signal, messages and initial values + signals = [ + # sig_name, sig_address, default + ("BrakePedalPosition", "EBCMBrakePedalPosition", 0), + ("FrontLeftDoor", "BCMDoorBeltStatus", 0), + ("FrontRightDoor", "BCMDoorBeltStatus", 0), + ("RearLeftDoor", "BCMDoorBeltStatus", 0), + ("RearRightDoor", "BCMDoorBeltStatus", 0), + ("LeftSeatBelt", "BCMDoorBeltStatus", 0), + ("RightSeatBelt", "BCMDoorBeltStatus", 0), + ("TurnSignals", "BCMTurnSignals", 0), + ("AcceleratorPedal", "AcceleratorPedal", 0), + ("ACCButtons", "ASCMSteeringButton", CruiseButtons.UNPRESS), + ("SteeringWheelAngle", "PSCMSteeringAngle", 0), + ("FLWheelSpd", "EBCMWheelSpdFront", 0), + ("FRWheelSpd", "EBCMWheelSpdFront", 0), + ("RLWheelSpd", "EBCMWheelSpdRear", 0), + ("RRWheelSpd", "EBCMWheelSpdRear", 0), + ("PRNDL", "ECMPRDNL", 0), + ("LKADriverAppldTrq", "PSCMStatus", 0), + ("LKATorqueDeliveredStatus", "PSCMStatus", 0), + ] + + if CP.carFingerprint in (CAR.VOLT, CAR.MALIBU): + signals += [ + ("RegenPaddle", "EBCMRegenPaddle", 0), + ] + if CP.carFingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + signals += [ + ("TractionControlOn", "ESPStatus", 0), + ("EPBClosed", "EPBStatus", 0), + ("CruiseMainOn", "ECMEngineStatus", 0), + ("CruiseState", "AcceleratorPedal2", 0), + ] + if CP.carFingerprint == CAR.CADILLAC_CT6: + signals += [ + ("ACCCmdActive", "ASCMActiveCruiseControlStatus", 0) + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, [], canbus.powertrain) + +class CarState(object): + def __init__(self, CP, canbus): + # initialize can parser + + self.car_fingerprint = CP.carFingerprint + self.cruise_buttons = CruiseButtons.UNPRESS + self.left_blinker_on = False + self.prev_left_blinker_on = False + self.right_blinker_on = False + self.prev_right_blinker_on = False + + # vEgo kalman filter + dt = 0.01 + self.v_ego_kf = KF1D(x0=np.matrix([[0.], [0.]]), + A=np.matrix([[1., dt], [0., 1.]]), + C=np.matrix([1., 0.]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0. + + def update(self, pt_cp): + + self.can_valid = pt_cp.can_valid + self.prev_cruise_buttons = self.cruise_buttons + self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]['ACCButtons'] + + self.v_wheel_fl = pt_cp.vl["EBCMWheelSpdFront"]['FLWheelSpd'] * CV.KPH_TO_MS + self.v_wheel_fr = pt_cp.vl["EBCMWheelSpdFront"]['FRWheelSpd'] * CV.KPH_TO_MS + self.v_wheel_rl = pt_cp.vl["EBCMWheelSpdRear"]['RLWheelSpd'] * CV.KPH_TO_MS + self.v_wheel_rr = pt_cp.vl["EBCMWheelSpdRear"]['RRWheelSpd'] * CV.KPH_TO_MS + speed_estimate = float(np.mean([self.v_wheel_fl, self.v_wheel_fr, self.v_wheel_rl, self.v_wheel_rr])) + + self.v_ego_raw = speed_estimate + v_ego_x = self.v_ego_kf.update(speed_estimate) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + + self.standstill = self.v_ego_raw < 0.01 + + self.angle_steers = pt_cp.vl["PSCMSteeringAngle"]['SteeringWheelAngle'] + self.gear_shifter = parse_gear_shifter(pt_cp.vl["ECMPRDNL"]['PRNDL']) + self.user_brake = pt_cp.vl["EBCMBrakePedalPosition"]['BrakePedalPosition'] + + self.pedal_gas = pt_cp.vl["AcceleratorPedal"]['AcceleratorPedal'] + self.user_gas_pressed = self.pedal_gas > 0 + + self.steer_torque_driver = pt_cp.vl["PSCMStatus"]['LKADriverAppldTrq'] + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD + + # 0 - inactive, 1 - active, 2 - temporary limited, 3 - failed + self.lkas_status = pt_cp.vl["PSCMStatus"]['LKATorqueDeliveredStatus'] + self.steer_not_allowed = not is_eps_status_ok(self.lkas_status, self.car_fingerprint) + + # 1 - open, 0 - closed + self.door_all_closed = (pt_cp.vl["BCMDoorBeltStatus"]['FrontLeftDoor'] == 0 and + pt_cp.vl["BCMDoorBeltStatus"]['FrontRightDoor'] == 0 and + pt_cp.vl["BCMDoorBeltStatus"]['RearLeftDoor'] == 0 and + pt_cp.vl["BCMDoorBeltStatus"]['RearRightDoor'] == 0) + + # 1 - latched + self.seatbelt = pt_cp.vl["BCMDoorBeltStatus"]['LeftSeatBelt'] == 1 + + self.steer_error = False + + self.brake_error = False + self.can_valid = True + + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + self.left_blinker_on = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 1 + self.right_blinker_on = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 2 + + if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + self.park_brake = pt_cp.vl["EPBStatus"]['EPBClosed'] + self.main_on = pt_cp.vl["ECMEngineStatus"]['CruiseMainOn'] + self.acc_active = False + self.esp_disabled = pt_cp.vl["ESPStatus"]['TractionControlOn'] != 1 + self.pcm_acc_status = pt_cp.vl["AcceleratorPedal2"]['CruiseState'] + if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU): + self.regen_pressed = bool(pt_cp.vl["EBCMRegenPaddle"]['RegenPaddle']) + else: + self.regen_pressed = False + if self.car_fingerprint == CAR.CADILLAC_CT6: + self.park_brake = False + self.main_on = False + self.acc_active = pt_cp.vl["ASCMActiveCruiseControlStatus"]['ACCCmdActive'] + self.esp_disabled = False + self.regen_pressed = False + self.pcm_acc_status = int(self.acc_active) + + # Brake pedal's potentiometer returns near-zero reading + # even when pedal is not pressed. + if self.user_brake < 10: + self.user_brake = 0 + + # Regen braking is braking + self.brake_pressed = self.user_brake > 10 or self.regen_pressed + + self.gear_shifter_valid = self.gear_shifter == car.CarState.GearShifter.drive diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py new file mode 100644 index 00000000000000..910cb1d95604ce --- /dev/null +++ b/selfdrive/car/gm/gmcan.py @@ -0,0 +1,190 @@ +def create_steering_control(packer, bus, apply_steer, idx, lkas_active): + + values = { + "LKASteeringCmdActive": lkas_active, + "LKASteeringCmd": apply_steer, + "RollingCounter": idx, + "LKASteeringCmdChecksum": 0x1000 - (lkas_active << 11) - (apply_steer & 0x7ff) - idx + } + + return packer.make_can_msg("ASCMLKASteeringCmd", bus, values) + +def create_steering_control_ct6(packer, canbus, apply_steer, v_ego, idx, enabled): + + values = { + "LKASteeringCmdActive": 1 if enabled else 0, + "LKASteeringCmd": apply_steer, + "RollingCounter": idx, + "SetMe1": 1, + "LKASVehicleSpeed": abs(v_ego * 3.6), + "LKASMode": 2 if enabled else 0, + "LKASteeringCmdChecksum": 0 # assume zero and then manually compute it + } + + dat = packer.make_can_msg("ASCMLKASteeringCmd", 0, values)[2] + # the checksum logic is weird + values['LKASteeringCmdChecksum'] = (0x2a + + sum([ord(i) for i in dat][:4]) + + values['LKASMode']) & 0x3ff + # pack again with checksum + dat = packer.make_can_msg("ASCMLKASteeringCmd", 0, values)[2] + + return [0x152, 0, dat, canbus.powertrain], \ + [0x154, 0, dat, canbus.powertrain], \ + [0x151, 0, dat, canbus.chassis], \ + [0x153, 0, dat, canbus.chassis] + + +def create_adas_keepalive(bus): + dat = "\x00\x00\x00\x00\x00\x00\x00" + return [[0x409, 0, dat, bus], [0x40a, 0, dat, bus]] + +def create_gas_regen_command(packer, bus, throttle, idx, acc_engaged, at_full_stop): + values = { + "GasRegenCmdActive": acc_engaged, + "RollingCounter": idx, + "GasRegenCmdActiveInv": 1 - acc_engaged, + "GasRegenCmd": throttle, + "GasRegenFullStopActive": at_full_stop, + "GasRegenAlwaysOne": 1, + "GasRegenAlwaysOne2": 1, + "GasRegenAlwaysOne3": 1, + } + + dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[2] + values["GasRegenChecksum"] = (((0xff - ord(dat[1])) & 0xff) << 16) | \ + (((0xff - ord(dat[2])) & 0xff) << 8) | \ + ((0x100 - ord(dat[3]) - idx) & 0xff) + + return packer.make_can_msg("ASCMGasRegenCmd", bus, values) + +def create_friction_brake_command(packer, bus, apply_brake, idx, near_stop, at_full_stop): + + if apply_brake == 0: + mode = 0x1 + else: + mode = 0xa + + if at_full_stop: + mode = 0xd + # TODO: this is to have GM bringing the car to complete stop, + # but currently it conflicts with OP controls, so turned off. + #elif near_stop: + # mode = 0xb + + brake = (0x1000 - apply_brake) & 0xfff + checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff + + values = { + "RollingCounter" : idx, + "FrictionBrakeMode" : mode, + "FrictionBrakeChecksum": checksum, + "FrictionBrakeCmd" : -apply_brake + } + + return packer.make_can_msg("EBCMFrictionBrakeCmd", bus, values) + +def create_acc_dashboard_command(packer, bus, acc_engaged, target_speed_kph, lead_car_in_sight): + # Not a bit shift, dash can round up based on low 4 bits. + target_speed = int(target_speed_kph * 16) & 0xfff + + values = { + "ACCAlwaysOne" : 1, + "ACCResumeButton" : 0, + "ACCSpeedSetpoint" : target_speed, + "ACCGapLevel" : 3 * acc_engaged, # 3 "far", 0 "inactive" + "ACCCmdActive" : acc_engaged, + "ACCAlwaysOne2" : 1, + "ACCLeadCar" : lead_car_in_sight + } + + return packer.make_can_msg("ASCMActiveCruiseControlStatus", bus, values) + +def create_adas_time_status(bus, tt, idx): + dat = [(tt >> 20) & 0xff, (tt >> 12) & 0xff, (tt >> 4) & 0xff, + ((tt & 0xf) << 4) + (idx << 2)] + chksum = 0x1000 - dat[0] - dat[1] - dat[2] - dat[3] + chksum = chksum & 0xfff + dat += [0x40 + (chksum >> 8), chksum & 0xff, 0x12] + return [0xa1, 0, "".join(map(chr, dat)), bus] + +def create_adas_steering_status(bus, idx): + dat = [idx << 6, 0xf0, 0x20, 0, 0, 0] + chksum = 0x60 + sum(dat) + dat += [chksum >> 8, chksum & 0xff] + return [0x306, 0, "".join(map(chr, dat)), bus] + +def create_adas_accelerometer_speed_status(bus, speed_ms, idx): + spd = int(speed_ms * 16) & 0xfff + accel = 0 & 0xfff + # 0 if in park/neutral, 0x10 if in reverse, 0x08 for D/L + #stick = 0x08 + near_range_cutoff = 0x27 + near_range_mode = 1 if spd <= near_range_cutoff else 0 + far_range_mode = 1 - near_range_mode + dat = [0x08, spd >> 4, ((spd & 0xf) << 4) | (accel >> 8), accel & 0xff, 0] + chksum = 0x62 + far_range_mode + (idx << 2) + dat[0] + dat[1] + dat[2] + dat[3] + dat[4] + dat += [(idx << 5) + (far_range_mode << 4) + (near_range_mode << 3) + (chksum >> 8), chksum & 0xff] + return [0x308, 0, "".join(map(chr, dat)), bus] + +def create_adas_headlights_status(bus): + return [0x310, 0, "\x42\x04", bus] + +def create_chime_command(bus, chime_type, duration, repeat_cnt): + dat = [chime_type, duration, repeat_cnt, 0xff, 0] + return [0x10400060, 0, "".join(map(chr, dat)), bus] + +def create_lka_icon_command(bus, active, critical): + if active: + if critical: + dat = "\x40\xc0\x14" + else: + dat = "\x40\x40\x18" + else: + dat = "\x00\x00\x00" + return [0x104c006c, 0, dat, bus] + +# TODO: WIP +''' +def create_friction_brake_command_ct6(packer, bus, apply_brake, idx, near_stop, at_full_stop): + + # counters loops across [0, 29, 42, 55] but checksum only considers 0, 1, 2, 3 + cntrs = [0, 29, 42, 55] + if apply_brake == 0: + mode = 0x1 + else: + mode = 0xa + + if at_full_stop: + mode = 0xd + elif near_stop: + mode = 0xb + + brake = (0x1000 - apply_brake) & 0xfff + checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff + + values = { + "RollingCounter" : cntrs[idx], + "FrictionBrakeMode" : mode, + "FrictionBrakeChecksum": checksum, + "FrictionBrakeCmd" : -apply_brake + } + + dat = packer.make_can_msg("EBCMFrictionBrakeCmd", 0, values)[2] + # msg is 0x315 but we are doing the panda forwarding + return [0x314, 0, dat, 2] + +def create_gas_regen_command_ct6(bus, throttle, idx, acc_engaged, at_full_stop): + cntrs = [0, 7, 10, 13] + eng_bit = 1 if acc_engaged else 0 + gas_high = (throttle >> 8) | 0x80 + gas_low = (throttle) & 0xff + full_stop = 0x20 if at_full_stop else 0 + + chk1 = (0x100 - gas_high - 1) & 0xff + chk2 = (0x100 - gas_low - idx) & 0xff + dat = [(idx << 6) | eng_bit, 0xc2 | full_stop, gas_high, gas_low, + (1 - eng_bit) | (cntrs[idx] << 1), 0x5d - full_stop, chk1, chk2] + return [0x2cb, 0, "".join(map(chr, dat)), bus] + +''' diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py new file mode 100755 index 00000000000000..8cf4e040bcd246 --- /dev/null +++ b/selfdrive/car/gm/interface.py @@ -0,0 +1,347 @@ +#!/usr/bin/env python +from cereal import car, log +from common.realtime import sec_since_boot +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.gm.values import DBC, CAR, STOCK_CONTROL_MSGS, AUDIO_HUD +from selfdrive.car.gm.carstate import CarState, CruiseButtons, get_powertrain_can_parser + +try: + from selfdrive.car.gm.carcontroller import CarController +except ImportError: + CarController = None + +class CanBus(object): + def __init__(self): + self.powertrain = 0 + self.obstacle = 1 + self.chassis = 2 + self.sw_gmlan = 3 + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + + self.frame = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.can_invalid_count = 0 + self.acc_active_prev = 0 + + # *** init the major players *** + canbus = CanBus() + self.CS = CarState(CP, canbus) + self.VM = VehicleModel(CP) + self.pt_cp = get_powertrain_can_parser(CP, canbus) + self.ch_cp_dbc_name = DBC[CP.carFingerprint]['chassis'] + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(canbus, CP.carFingerprint, CP.enableCamera) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 4.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + ret = car.CarParams.new_message() + + ret.carName = "gm" + ret.carFingerprint = candidate + + ret.enableCruise = False + + # Presence of a camera on the object bus is ok. + # Have to go passive if ASCM is online (ACC-enabled cars), + # or camera is on powertrain bus (LKA cars without ACC). + ret.enableCamera = not any(x for x in STOCK_CONTROL_MSGS[candidate] if x in fingerprint) + + std_cargo = 136 + + if candidate == CAR.VOLT: + # supports stop and go, but initial engage must be above 18mph (which include conservatism) + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + # kg of standard extra cargo to count for driver, gas, etc... + ret.mass = 1607 + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.wheelbase = 2.69 + ret.steerRatio = 15.7 + ret.steerRatioRear = 0. + ret.centerToFront = ret.wheelbase * 0.4 # wild guess + + elif candidate == CAR.MALIBU: + # supports stop and go, but initial engage must be above 18mph (which include conservatism) + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + ret.mass = 1496 + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.wheelbase = 2.83 + ret.steerRatio = 15.8 + ret.steerRatioRear = 0. + ret.centerToFront = ret.wheelbase * 0.4 # wild guess + + elif candidate == CAR.HOLDEN_ASTRA: + # kg of standard extra cargo to count for driver, gas, etc... + ret.mass = 1363 + std_cargo + ret.wheelbase = 2.662 + # Remaining parameters copied from Volt for now + ret.centerToFront = ret.wheelbase * 0.4 + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.steerRatio = 15.7 + ret.steerRatioRear = 0. + + elif candidate == CAR.ACADIA: + ret.minEnableSpeed = -1 # engage speed is decided by pcm + ret.mass = 4353. * CV.LB_TO_KG + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.wheelbase = 2.86 + ret.steerRatio = 14.4 #end to end is 13.46 + ret.steerRatioRear = 0. + ret.centerToFront = ret.wheelbase * 0.4 + + elif candidate == CAR.CADILLAC_CT6: + # engage speed is decided by pcm + ret.minEnableSpeed = -1 + # kg of standard extra cargo to count for driver, gas, etc... + ret.mass = 4016. * CV.LB_TO_KG + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.cadillac + ret.wheelbase = 3.11 + ret.steerRatio = 14.6 # it's 16.3 without rear active steering + ret.steerRatioRear = 0. # TODO: there is RAS on this car! + ret.centerToFront = ret.wheelbase * 0.465 + + + # hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923. * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 85400 + tireStiffnessRear_civic = 90000 + + centerToRear = ret.wheelbase - ret.centerToFront + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = tireStiffnessFront_civic * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = tireStiffnessRear_civic * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + + # same tuning for Volt and CT6 for now + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.2], [0.00]] + ret.steerKf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 + + ret.steerMaxBP = [0.] # m/s + ret.steerMaxV = [1.] + ret.gasMaxBP = [0.] + ret.gasMaxV = [.5] + ret.brakeMaxBP = [0.] + ret.brakeMaxV = [1.] + ret.longPidDeadzoneBP = [0.] + ret.longPidDeadzoneV = [0.] + + ret.longitudinalKpBP = [5., 35.] + ret.longitudinalKpV = [2.4, 1.5] + ret.longitudinalKiBP = [0.] + ret.longitudinalKiV = [0.36] + + ret.steerLimitAlert = True + + ret.stoppingControl = True + ret.startAccel = 0.8 + + ret.steerActuatorDelay = 0.1 # Default delay, not measured yet + ret.steerRateCost = 1.0 + ret.steerControlType = car.CarParams.SteerControlType.torque + + return ret + + # returns a car.CarState + def update(self, c): + + self.pt_cp.update(int(sec_since_boot() * 1e9), False) + self.CS.update(self.pt_cp) + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.CS.v_ego + ret.aEgo = self.CS.a_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.yawRate = self.VM.yaw_rate(self.CS.angle_steers * CV.DEG_TO_RAD, self.CS.v_ego) + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # gas pedal information. + ret.gas = self.CS.pedal_gas / 254.0 + ret.gasPressed = self.CS.user_gas_pressed + + # brake pedal + ret.brake = self.CS.user_brake / 0xd0 + ret.brakePressed = self.CS.brake_pressed + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + + # torque and user override. Driver awareness + # timer resets when the user uses the steering wheel. + ret.steeringPressed = self.CS.steer_override + ret.steeringTorque = self.CS.steer_torque_driver + + # cruise state + ret.cruiseState.available = bool(self.CS.main_on) + cruiseEnabled = self.CS.pcm_acc_status != 0 + ret.cruiseState.enabled = cruiseEnabled + ret.cruiseState.standstill = self.CS.pcm_acc_status == 4 + + ret.leftBlinker = self.CS.left_blinker_on + ret.rightBlinker = self.CS.right_blinker_on + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + ret.gearShifter = self.CS.gear_shifter + + buttonEvents = [] + + # blinkers + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'leftBlinker' + be.pressed = self.CS.left_blinker_on + buttonEvents.append(be) + + if self.CS.right_blinker_on != self.CS.prev_right_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'rightBlinker' + be.pressed = self.CS.right_blinker_on + buttonEvents.append(be) + + if self.CS.cruise_buttons != self.CS.prev_cruise_buttons: + be = car.CarState.ButtonEvent.new_message() + be.type = 'unknown' + if self.CS.cruise_buttons != CruiseButtons.UNPRESS: + be.pressed = True + but = self.CS.cruise_buttons + else: + be.pressed = False + but = self.CS.prev_cruise_buttons + if but == CruiseButtons.RES_ACCEL: + if not (cruiseEnabled and self.CS.standstill): + be.type = 'accelCruise' # Suppress resume button if we're resuming from stop so we don't adjust speed. + elif but == CruiseButtons.DECEL_SET: + be.type = 'decelCruise' + elif but == CruiseButtons.CANCEL: + be.type = 'cancel' + elif but == CruiseButtons.MAIN: + be.type = 'altButton3' + buttonEvents.append(be) + + ret.buttonEvents = buttonEvents + + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + if self.CS.steer_error: + events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + if self.CS.steer_not_allowed: + events.append(create_event('steerTempUnavailable', [ET.NO_ENTRY, ET.WARNING])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.seatbeltUnlatched: + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + + if self.CS.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + if self.CS.brake_error: + events.append(create_event('brakeUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + if not self.CS.gear_shifter_valid: + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.esp_disabled: + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if not self.CS.main_on: + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if self.CS.gear_shifter == 3: + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if ret.vEgo < self.CP.minEnableSpeed: + events.append(create_event('speedTooLow', [ET.NO_ENTRY])) + if self.CS.park_brake: + events.append(create_event('parkBrake', [ET.NO_ENTRY, ET.USER_DISABLE])) + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed): # and (not self.brake_pressed_prev or ret.vEgo > 0.001)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + if ret.cruiseState.standstill: + events.append(create_event('resumeRequired', [ET.WARNING])) + + # handle button presses + for b in ret.buttonEvents: + # do enable on both accel and decel buttons + if b.type in ["accelCruise", "decelCruise"] and not b.pressed: + events.append(create_event('buttonEnable', [ET.ENABLE])) + # do disable on button down + if b.type == "cancel" and b.pressed: + events.append(create_event('buttonCancel', [ET.USER_DISABLE])) + + if self.CS.car_fingerprint == CAR.CADILLAC_CT6: + + if self.CS.acc_active and not self.acc_active_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + if not self.CS.acc_active: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + ret.events = events + + # update previous brake/gas pressed + self.acc_active_prev = self.CS.acc_active + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + + # cast to reader so it can't be modified + return ret.as_reader() + + # pass in a car.CarControl + # to be called @ 100hz + def apply(self, c, perception_state=log.Live20Data.new_message()): + hud_v_cruise = c.hudControl.setSpeed + if hud_v_cruise > 70: + hud_v_cruise = 0 + + chime, chime_count = AUDIO_HUD[c.hudControl.audibleAlert.raw] + + # For Openpilot, "enabled" includes pre-enable. + # In GM, PCM faults out if ACC command overlaps user gas. + enabled = c.enabled and not self.CS.user_gas_pressed + + self.CC.update(self.sendcan, enabled, self.CS, self.frame, \ + c.actuators, + hud_v_cruise, c.hudControl.lanesVisible, \ + c.hudControl.leadVisible, \ + chime, chime_count) + + self.frame += 1 diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py new file mode 100755 index 00000000000000..af10aa5ad144ba --- /dev/null +++ b/selfdrive/car/gm/radar_interface.py @@ -0,0 +1,127 @@ +#!/usr/bin/env python +import zmq +import math +import time +import numpy as np +from cereal import car +from selfdrive.can.parser import CANParser +from selfdrive.car.gm.interface import CanBus +from selfdrive.car.gm.values import DBC, CAR +from common.realtime import sec_since_boot +from selfdrive.services import service_list +import selfdrive.messaging as messaging + +RADAR_HEADER_MSG = 1120 +SLOT_1_MSG = RADAR_HEADER_MSG + 1 +NUM_SLOTS = 20 + +# Actually it's 0x47f, but can parser only reports +# messages that are present in DBC +LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS + +def create_radard_can_parser(canbus, car_fingerprint): + + dbc_f = DBC[car_fingerprint]['radar'] + if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + # C1A-ARS3-A by Continental + radar_targets = range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS) + signals = zip(['FLRRNumValidTargets', + 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', + 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', + 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + + ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, + [RADAR_HEADER_MSG] * 7 + radar_targets * 6, + [0] * 7 + + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + + [0.0] * NUM_SLOTS + [0] * NUM_SLOTS) + + checks = [] + + return CANParser(dbc_f, signals, checks, canbus.obstacle) + else: + return None + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + + self.delay = 0.0 # Delay of radar + + canbus = CanBus() + print "Using %d as obstacle CAN bus ID" % canbus.obstacle + self.rcp = create_radard_can_parser(canbus, CP.carFingerprint) + + context = zmq.Context() + self.logcan = messaging.sub_sock(context, service_list['can'].port) + + def update(self): + updated_messages = set() + ret = car.RadarState.new_message() + while 1: + + if self.rcp is None: + time.sleep(0.05) # nothing to do + return ret + + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + if LAST_RADAR_MSG in updated_messages: + break + + header = self.rcp.vl[RADAR_HEADER_MSG] + fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ + header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ + header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + if fault: + errors.append("fault") + ret.errors = errors + + currentTargets = set() + num_targets = header['FLRRNumValidTargets'] + + # Not all radar messages describe targets, + # no need to monitor all of the self.rcp.msgs_upd + for ii in updated_messages: + if ii == RADAR_HEADER_MSG: + continue + + if num_targets == 0: + break + + cpt = self.rcp.vl[ii] + # Zero distance means it's an empty target slot + if cpt['TrkRange'] > 0.0: + targetId = cpt['TrkObjectID'] + currentTargets.add(targetId) + if targetId not in self.pts: + self.pts[targetId] = car.RadarState.RadarPoint.new_message() + self.pts[targetId].trackId = targetId + distance = cpt['TrkRange'] + self.pts[targetId].dRel = distance # from front of car + # From driver's pov, left is positive + deg_to_rad = np.pi/180. + self.pts[targetId].yRel = math.sin(deg_to_rad * cpt['TrkAzimuth']) * distance + self.pts[targetId].vRel = cpt['TrkRangeRate'] + self.pts[targetId].aRel = float('nan') + self.pts[targetId].yvRel = float('nan') + + for oldTarget in self.pts.keys(): + if not oldTarget in currentTargets: + del self.pts[oldTarget] + + ret.points = self.pts.values() + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print ret diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py new file mode 100644 index 00000000000000..d6dd2cdba78cfb --- /dev/null +++ b/selfdrive/car/gm/values.py @@ -0,0 +1,104 @@ +from cereal import car +from selfdrive.car import dbc_dict + +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + +class CAR: + HOLDEN_ASTRA = "HOLDEN ASTRA RS-V BK 2017" + VOLT = "CHEVROLET VOLT PREMIER 2017" + CADILLAC_CT6 = "CADILLAC CT6 SUPERCRUISE 2018" + MALIBU = "CHEVROLET MALIBU PREMIER 2017" + ACADIA = "GMC ACADIA DENALI 2018" + +class CruiseButtons: + UNPRESS = 1 + RES_ACCEL = 2 + DECEL_SET = 3 + MAIN = 5 + CANCEL = 6 + +# Car chimes, beeps, blinker sounds etc +class CM: + TOCK = 0x81 + TICK = 0x82 + LOW_BEEP = 0x84 + HIGH_BEEP = 0x85 + LOW_CHIME = 0x86 + HIGH_CHIME = 0x87 + +AUDIO_HUD = { + AudibleAlert.none: (0, 0), + AudibleAlert.chimeEngage: (CM.HIGH_CHIME, 1), + AudibleAlert.chimeDisengage: (CM.HIGH_CHIME, 1), + AudibleAlert.chimeError: (CM.LOW_CHIME, 2), + AudibleAlert.chimePrompt: (CM.LOW_CHIME, 1), + AudibleAlert.chimeWarning1: (CM.LOW_CHIME, 2), + AudibleAlert.chimeWarning2: (CM.LOW_CHIME, -1), + AudibleAlert.chimeWarningRepeat: (CM.LOW_CHIME, -1)} + +def is_eps_status_ok(eps_status, car_fingerprint): + valid_eps_status = [] + if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA): + valid_eps_status += [0, 1] + elif car_fingerprint == CAR.CADILLAC_CT6: + valid_eps_status += [0, 1, 4, 5, 6] + return eps_status in valid_eps_status + +def parse_gear_shifter(can_gear): + if can_gear == 0: + return car.CarState.GearShifter.park + elif can_gear == 1: + return car.CarState.GearShifter.neutral + elif can_gear == 2: + return car.CarState.GearShifter.drive + elif can_gear == 3: + return car.CarState.GearShifter.reverse + else: + return car.CarState.GearShifter.unknown + +FINGERPRINTS = { + # Astra BK MY17, ASCM unplugged + CAR.HOLDEN_ASTRA: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7, + }], + CAR.VOLT: [ + # Volt Premier w/ ACC 2017 + { + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 + }, + # Volt Premier w/ ACC 2018 + { + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 + }], + CAR.CADILLAC_CT6: [{ + 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, 313: 8, 320: 3, 322: 7, 328: 1, 336: 1, 338: 6, 340: 6, 352: 5, 354: 5, 356: 8, 368: 3, 372: 5, 381: 8, 386: 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, 458: 5, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 800: 6, 801: 8, 804: 3, 810: 8, 832: 8, 833: 8, 834: 8, 835: 6, 836: 5, 837: 8, 838: 8, 839: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 884: 8, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 1, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1934: 7, 2016: 8, 2024: 8 + }], + CAR.MALIBU: [ + # Malibu Premier w/ ACC 2017 + { + 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, 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 + }], +} + +STEER_THRESHOLD = 1.0 + +STOCK_CONTROL_MSGS = { + CAR.HOLDEN_ASTRA: [384, 715], + CAR.VOLT: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" + CAR.MALIBU: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" + CAR.ACADIA: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" + CAR.CADILLAC_CT6: [], # Cadillac does not require ASCMs to be disconnected +} + +DBC = { + CAR.HOLDEN_ASTRA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.VOLT: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.MALIBU: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.ACADIA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.CADILLAC_CT6: dbc_dict('cadillac_ct6_powertrain', 'cadillac_ct6_object', chassis_dbc='cadillac_ct6_chassis'), +} diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 1ee7e2c8089afa..1cb9830e39f26e 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -1,24 +1,19 @@ from collections import namedtuple -import os -import common.numpy_fast as np -from common.numpy_fast import clip, interp from common.realtime import sec_since_boot - -from selfdrive.config import CruiseButtons from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.controls.lib.drive_helpers import rate_limit +from common.numpy_fast import clip +from selfdrive.car.honda import hondacan +from selfdrive.car.honda.values import AH, CruiseButtons, CAR +from selfdrive.can.packer import CANPacker -from . import hondacan -from .values import AH - - -def actuator_hystereses(brake, braking, brake_steady, v_ego, civic): - # hyst params... TODO: move these to VehicleParams +def actuator_hystereses(brake, braking, brake_steady, v_ego, car_fingerprint): + # hyst params brake_hyst_on = 0.02 # to activate brakes exceed this value brake_hyst_off = 0.005 # to deactivate brakes below this value brake_hyst_gap = 0.01 # don't change brake command for small ocilalitons within this value - #*** histeresys logic to avoid brake blinking. go above 0.1 to trigger + #*** histeresis logic to avoid brake blinking. go above 0.1 to trigger if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: brake = 0. braking = brake > 0. @@ -32,12 +27,30 @@ def actuator_hystereses(brake, braking, brake_steady, v_ego, civic): brake_steady = brake + brake_hyst_gap brake = brake_steady - if not civic and brake > 0.0: + if (car_fingerprint in (CAR.ACURA_ILX, CAR.CRV)) and brake > 0.0: brake += 0.15 return brake, braking, brake_steady +def brake_pump_hysteresys(apply_brake, apply_brake_last, last_pump_ts): + ts = sec_since_boot() + pump_on = False + + # reset pump timer if: + # - there is an increment in brake request + # - we are applying steady state brakes and we haven't been running the pump + # for more than 20s (to prevent pressure bleeding) + if apply_brake > apply_brake_last or (ts - last_pump_ts > 20 and apply_brake > 0): + last_pump_ts = ts + + # once the pump is on, run it for at least 0.2s + if ts - last_pump_ts < 0.2 and apply_brake > 0: + pump_on = True + + return pump_on, last_pump_ts + + def process_hud_alert(hud_alert): # initialize to no alert fcw_display = 0 @@ -56,29 +69,33 @@ def process_hud_alert(hud_alert): HUDData = namedtuple("HUDData", - ["pcm_accel", "v_cruise", "X2", "car", "X4", "X5", - "lanes", "beep", "X8", "chime", "acc_alert"]) + ["pcm_accel", "v_cruise", "mini_car", "car", "X4", + "lanes", "beep", "chime", "fcw", "acc_alert", "steer_required"]) class CarController(object): - def __init__(self, enable_camera=True): + def __init__(self, dbc_name, enable_camera=True): self.braking = False self.brake_steady = 0. self.brake_last = 0. + self.apply_brake_last = 0 + self.last_pump_ts = 0 self.enable_camera = enable_camera + self.packer = CANPacker(dbc_name) + self.new_radar_config = False def update(self, sendcan, enabled, CS, frame, actuators, \ pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ - hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert, \ - snd_beep, snd_chime): + radar_error, hud_v_cruise, hud_show_lanes, hud_show_car, \ + hud_alert, snd_beep, snd_chime): + """ Controls thread """ - # TODO: Make the accord work. - if CS.accord or not self.enable_camera: + if not self.enable_camera: return # *** apply brake hysteresis *** - brake, self.braking, self.brake_steady = actuator_hystereses(actuators.brake, self.braking, self.brake_steady, CS.v_ego, CS.civic) + brake, self.braking, self.brake_steady = actuator_hystereses(actuators.brake, self.braking, self.brake_steady, CS.v_ego, CS.CP.carFingerprint) # *** no output if not enabled *** if not enabled and CS.pcm_acc_status: @@ -89,92 +106,79 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ self.brake_last = rate_limit(brake, self.brake_last, -2., 1./100) # vehicle hud display, wait for one update from 10Hz 0x304 msg - #TODO: use enum!! if hud_show_lanes: - hud_lanes = 0x04 + hud_lanes = 1 else: - hud_lanes = 0x00 + hud_lanes = 0 - # TODO: factor this out better if enabled: if hud_show_car: - hud_car = 0xe0 + hud_car = 2 else: - hud_car = 0xd0 + hud_car = 1 else: - hud_car = 0xc0 + hud_car = 0 + + # For lateral control-only, send chimes as a beep since we don't send 0x1fa + if CS.CP.radarOffCan: + snd_beep = snd_beep if snd_beep is not 0 else snd_chime #print chime, alert_id, hud_alert fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert) - hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), 0x01, hud_car, - 0xc1, 0x41, hud_lanes + steer_required, - int(snd_beep), 0x48, (snd_chime << 5) + fcw_display, acc_alert) - - if not all(isinstance(x, int) and 0 <= x < 256 for x in hud): - print "INVALID HUD", hud - hud = HUDData(0xc6, 255, 64, 0xc0, 209, 0x41, 0x40, 0, 0x48, 0, 0) + hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), 1, hud_car, + 0xc1, hud_lanes, int(snd_beep), snd_chime, fcw_display, acc_alert, steer_required) # **** process the car messages **** # *** compute control surfaces *** - tt = sec_since_boot() - GAS_MAX = 1004 BRAKE_MAX = 1024/4 - if CS.civic: - is_fw_modified = os.getenv("DONGLE_ID") in ['b0f5a01cf604185c'] - STEER_MAX = 0x1FFF if is_fw_modified else 0x1000 - elif CS.crv: - STEER_MAX = 0x300 # CR-V only uses 12-bits and requires a lower value - else: + if CS.CP.carFingerprint in (CAR.ACURA_ILX): STEER_MAX = 0xF00 - GAS_OFFSET = 328 + elif CS.CP.carFingerprint in (CAR.CRV, CAR.ACURA_RDX): + STEER_MAX = 0x3e8 # CR-V only uses 12-bits and requires a lower value (max value from energee) + else: + STEER_MAX = 0x1000 # steer torque is converted back to CAN reference (positive when steering right) - apply_gas = int(clip(actuators.gas * GAS_MAX, 0, GAS_MAX - 1)) + apply_gas = clip(actuators.gas, 0., 1.) apply_brake = int(clip(self.brake_last * BRAKE_MAX, 0, BRAKE_MAX - 1)) apply_steer = int(clip(-actuators.steer * STEER_MAX, -STEER_MAX, STEER_MAX)) - # any other cp.vl[0x18F]['STEER_STATUS'] is common and can happen during user override. sending 0 torque to avoid EPS sending error 5 - if CS.steer_not_allowed: - apply_steer = 0 + lkas_active = enabled and not CS.steer_not_allowed # Send CAN commands. can_sends = [] # Send steering command. - if CS.accord: - idx = frame % 2 - can_sends.append(hondacan.create_accord_steering_control(apply_steer, idx)) - else: - idx = frame % 4 - can_sends.extend(hondacan.create_steering_control(apply_steer, CS.crv, idx)) - - # Send gas and brake commands. - if (frame % 2) == 0: - idx = (frame / 2) % 4 - can_sends.append( - hondacan.create_brake_command(apply_brake, pcm_override, - pcm_cancel_cmd, hud.chime, idx)) - if not CS.brake_only: - # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. - # This prevents unexpected pedal range rescaling - gas_amount = (apply_gas + GAS_OFFSET) * (apply_gas > 0) - can_sends.append(hondacan.create_gas_command(gas_amount, idx)) + idx = frame % 4 + can_sends.append(hondacan.create_steering_control(self.packer, apply_steer, + lkas_active, CS.CP.carFingerprint, idx)) # Send dashboard UI commands. if (frame % 10) == 0: idx = (frame/10) % 4 - can_sends.extend(hondacan.create_ui_commands(pcm_speed, hud, CS.civic, CS.accord, CS.crv, idx)) + can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, idx)) - # radar at 20Hz, but these msgs need to be sent at 50Hz on ilx (seems like an Acura bug) - if CS.civic or CS.accord or CS.crv: - radar_send_step = 5 - else: - radar_send_step = 2 + if CS.CP.radarOffCan: + # If using stock ACC, spam cancel command to kill gas when OP disengages. + if pcm_cancel_cmd: + can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.CANCEL, idx)) + elif CS.stopped: + can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.RES_ACCEL, idx)) - if (frame % radar_send_step) == 0: - idx = (frame/radar_send_step) % 4 - can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.civic, CS.accord, CS.crv, idx)) + else: + # Send gas and brake commands. + if (frame % 2) == 0: + idx = (frame / 2) % 4 + pump_on, self.last_pump_ts = brake_pump_hysteresys(apply_brake, self.apply_brake_last, self.last_pump_ts) + can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on, + pcm_override, pcm_cancel_cmd, hud.chime, hud.fcw, idx)) + self.apply_brake_last = apply_brake + + if CS.CP.enableGasInterceptor: + # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. + # This prevents unexpected pedal range rescaling + can_sends.append(hondacan.create_gas_command(self.packer, apply_gas, idx)) sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 015ff7c5737920..f46343c18fc7d6 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -1,41 +1,18 @@ -import os -from cereal import car from common.numpy_fast import interp -import selfdrive.messaging as messaging -from selfdrive.can.parser import CANParser +from common.kalman.simple_kalman import KF1D +from selfdrive.can.parser import CANParser, CANDefine from selfdrive.config import Conversions as CV -import numpy as np +from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, SPEED_FACTOR, HONDA_BOSCH -def parse_gear_shifter(can_gear_shifter, is_acura): +def parse_gear_shifter(gear, vals): - if can_gear_shifter == 0x1: - return "park" - elif can_gear_shifter == 0x2: - return "reverse" + val_to_capnp = {'P': 'park', 'R': 'reverse', 'N': 'neutral', + 'D': 'drive', 'S': 'sport', 'L': 'low'} + try: + return val_to_capnp[vals[gear]] + except KeyError: + return "unknown" - if is_acura: - if can_gear_shifter == 0x3: - return "neutral" - elif can_gear_shifter == 0x4: - return "drive" - elif can_gear_shifter == 0xa: - return "sport" - - else: - if can_gear_shifter == 0x4: - return "neutral" - elif can_gear_shifter == 0x8: - return "drive" - elif can_gear_shifter == 0x10: - return "sport" - elif can_gear_shifter == 0x20: - return "low" - - return "unknown" - -_K0 = -0.3 -_K1 = -0.01879 -_K2 = 0.01013 def calc_cruise_offset(offset, speed): # euristic formula so that speed is controlled to ~ 0.3m/s below pid_speed @@ -43,254 +20,132 @@ def calc_cruise_offset(offset, speed): # - speed = 0m/s, out = -0.3 # - speed = 34m/s, offset = 20, out = -0.25 # - speed = 34m/s, offset = -2.5, out = -1.8 + _K0 = -0.3 + _K1 = -0.01879 + _K2 = 0.01013 return min(_K0 + _K1 * speed + _K2 * speed * offset, 0.) + def get_can_signals(CP): # this function generates lists for signal, messages and initial values - if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": - dbc_f = 'honda_civic_touring_2016_can.dbc' - signals = [ - # sig_name, sig_address, default - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x14a, 0), - ("STEER_ANGLE_RATE", 0x14a, 0), - ("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x191, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - ("CAR_GAS", 0x130, 0), - ("CRUISE_BUTTONS", 0x296, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - ("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x191, 0), - ("MAIN_ON", 0x326, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x296, 0), - ("LEFT_BLINKER", 0x326, 0), - ("RIGHT_BLINKER", 0x326, 0), - ("CRUISE_SPEED_OFFSET", 0x37c, 0), - ("EPB_STATE", 0x1c2, 0), - ("BRAKE_HOLD_ACTIVE", 0x1A4, 0), - ] - checks = [ - # address, frequency - (0x14a, 100), - (0x158, 100), - (0x17c, 100), - (0x191, 100), - (0x1a4, 50), - (0x326, 10), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x37c, 10), - (0x405, 3), - ] - - elif CP.carFingerprint == "ACURA ILX 2016 ACURAWATCH PLUS": - dbc_f = 'acura_ilx_2016_can.dbc' - signals = [ - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x156, 0), - ("STEER_ANGLE_RATE", 0x156, 0), - ("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x1a3, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - ("CAR_GAS", 0x130, 0), - ("CRUISE_BUTTONS", 0x1a6, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - ("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x1a3, 0), - ("MAIN_ON", 0x1a6, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x1a6, 0), - ("LEFT_BLINKER", 0x294, 0), - ("RIGHT_BLINKER", 0x294, 0), - ("CRUISE_SPEED_OFFSET", 0x37c, 0) - ] - checks = [ - (0x156, 100), - (0x158, 100), - (0x17c, 100), - (0x1a3, 50), - (0x1a4, 50), - (0x1a6, 50), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x37c, 10), - (0x405, 3), - ] - elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": - dbc_f = 'honda_accord_touring_2016_can.dbc' - signals = [ - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x156, 0), - ("STEER_ANGLE_RATE", 0x156, 0), - #("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x191, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - #("CAR_GAS", 0x130, 0), - ("PEDAL_GAS", 0x17C, 0), - ("CRUISE_BUTTONS", 0x1a6, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - #("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x191, 0), - ("MAIN_ON", 0x1a6, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x1a6, 0), - ("LEFT_BLINKER", 0x294, 0), - ("RIGHT_BLINKER", 0x294, 0), - ] - checks = [ - (0x156, 100), - (0x158, 100), - (0x17c, 100), - (0x191, 100), - (0x1a4, 50), - (0x1a6, 50), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x405, 3), - ] - elif CP.carFingerprint == "HONDA CR-V 2016 TOURING": - dbc_f = 'honda_crv_touring_2016_can.dbc' - signals = [ - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x156, 0), - ("STEER_ANGLE_RATE", 0x156, 0), - ("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x191, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - #("CAR_GAS", 0x130, 0), - ("CRUISE_BUTTONS", 0x1a6, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - ("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x191, 0), - ("MAIN_ON", 0x1a6, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x1a6, 0), - ("LEFT_BLINKER", 0x294, 0), - ("RIGHT_BLINKER", 0x294, 0), - ] - checks = [ - (0x156, 100), - (0x158, 100), - (0x17c, 100), - (0x191, 100), - (0x1a4, 50), - (0x1a6, 50), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x405, 3), - ] + signals = [ + ("XMISSION_SPEED", "ENGINE_DATA", 0), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), + ("STEER_ANGLE", "STEERING_SENSORS", 0), + ("STEER_ANGLE_RATE", "STEERING_SENSORS", 0), + ("STEER_TORQUE_SENSOR", "STEER_STATUS", 0), + ("LEFT_BLINKER", "SCM_FEEDBACK", 0), + ("RIGHT_BLINKER", "SCM_FEEDBACK", 0), + ("GEAR", "GEARBOX", 0), + ("BRAKE_ERROR_1", "STANDSTILL", 1), + ("BRAKE_ERROR_2", "STANDSTILL", 1), + ("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS", 1), + ("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS", 0), + ("BRAKE_PRESSED", "POWERTRAIN_DATA", 0), + ("BRAKE_SWITCH", "POWERTRAIN_DATA", 0), + ("CRUISE_BUTTONS", "SCM_BUTTONS", 0), + ("ESP_DISABLED", "VSA_STATUS", 1), + ("HUD_LEAD", "ACC_HUD", 0), + ("USER_BRAKE", "VSA_STATUS", 0), + ("STEER_STATUS", "STEER_STATUS", 5), + ("GEAR_SHIFTER", "GEARBOX", 0), + ("PEDAL_GAS", "POWERTRAIN_DATA", 0), + ("CRUISE_SETTING", "SCM_BUTTONS", 0), + ("ACC_STATUS", "POWERTRAIN_DATA", 0), + ] + + checks = [ + ("ENGINE_DATA", 100), + ("WHEEL_SPEEDS", 50), + ("STEERING_SENSORS", 100), + ("SCM_FEEDBACK", 10), + ("GEARBOX", 100), + ("STANDSTILL", 50), + ("SEATBELT_STATUS", 10), + ("CRUISE", 10), + ("POWERTRAIN_DATA", 100), + ("VSA_STATUS", 50), + ("SCM_BUTTONS", 25), + ] + + if CP.radarOffCan: + # Civic is only bosch to use the same brake message as other hondas. + if CP.carFingerprint not in (CAR.ACCORDH, CAR.CIVIC_HATCH): + signals += [("BRAKE_PRESSED", "BRAKE_MODULE", 0)] + checks += [("BRAKE_MODULE", 50)] + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0), + ("CRUISE_SPEED", "ACC_HUD", 0)] + checks += [("GAS_PEDAL_2", 100)] + else: + # Nidec signals. + signals += [("CRUISE_SPEED_PCM", "CRUISE", 0), + ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS", 0)] + checks += [("CRUISE_PARAMS", 50)] + + if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH): + signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)] + else: + signals += [("DOOR_OPEN_FL", "DOORS_STATUS", 1), + ("DOOR_OPEN_FR", "DOORS_STATUS", 1), + ("DOOR_OPEN_RL", "DOORS_STATUS", 1), + ("DOOR_OPEN_RR", "DOORS_STATUS", 1), + ("WHEELS_MOVING", "STANDSTILL", 1)] + checks += [("DOORS_STATUS", 3)] + + if CP.carFingerprint == CAR.CIVIC: + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + elif CP.carFingerprint == CAR.ACURA_ILX: + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_BUTTONS", 0)] + elif CP.carFingerprint in (CAR.CRV, CAR.ACURA_RDX, CAR.PILOT_2019, CAR.RIDGELINE): + signals += [("MAIN_ON", "SCM_BUTTONS", 0)] + elif CP.carFingerprint == CAR.ODYSSEY: + signals += [("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + checks += [("EPB_STATUS", 50)] + elif CP.carFingerprint == CAR.PILOT: + signals += [("MAIN_ON", "SCM_BUTTONS", 0), + ("CAR_GAS", "GAS_PEDAL_2", 0)] + # add gas interceptor reading if we are using it - if CP.enableGas: - signals.append(("INTERCEPTOR_GAS", 0x201, 0)) - checks.append((0x201, 50)) + if CP.enableGasInterceptor: + signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR", 0)) + checks.append(("GAS_SENSOR", 50)) + + return signals, checks - return dbc_f, signals, checks def get_can_parser(CP): - dbc_f, signals, checks = get_can_signals(CP) - return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 0) + signals, checks = get_can_signals(CP) + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + +def get_cam_can_parser(CP): + signals = [] + + # all hondas except CRV and RDX use 0xe4 for steering + checks = [(0xe4, 100)] + if CP.carFingerprint in [CAR.CRV, CAR.ACURA_RDX]: + checks = [(0x194, 100)] + + cam_bus = 1 if CP.carFingerprint in HONDA_BOSCH else 2 + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, cam_bus) class CarState(object): def __init__(self, CP): - self.acura = False - self.civic = False - self.accord = False - self.crv = False - if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": - self.civic = True - elif CP.carFingerprint == "ACURA ILX 2016 ACURAWATCH PLUS": - self.acura = True - elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": - self.accord = True - elif CP.carFingerprint == "HONDA CR-V 2016 TOURING": - self.crv = True - else: - raise ValueError("unsupported car %s" % CP.carFingerprint) - - self.brake_only = CP.enableCruise self.CP = CP + self.can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + self.shifter_values = self.can_define.dv["GEARBOX"]["GEAR_SHIFTER"] self.user_gas, self.user_gas_pressed = 0., 0 self.brake_switch_prev = 0 @@ -298,31 +153,32 @@ def __init__(self, CP): self.cruise_buttons = 0 self.cruise_setting = 0 + self.v_cruise_pcm_prev = 0 self.blinker_on = 0 self.left_blinker_on = 0 self.right_blinker_on = 0 + self.stopped = 0 + # vEgo kalman filter dt = 0.01 - self.v_ego_x = np.matrix([[0.0], [0.0]]) - self.v_ego_A = np.matrix([[1.0, dt], [0.0, 1.0]]) - self.v_ego_C = np.matrix([1.0, 0.0]) - self.v_ego_Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) - self.v_ego_R = 1e3 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=[[0.0], [0.0]], + A=[[1.0, dt], [0.0, 1.0]], + C=[[1.0, 0.0]], + K=[[0.12287673], [0.29666309]]) self.v_ego = 0.0 - # import control - # (x, l, K) = control.dare(np.transpose(A), np.transpose(C), Q, R) - # self.v_ego_K = np.transpose(K) - self.v_ego_K = np.matrix([[0.12287673], [0.29666309]]) - def update(self, cp): + def update(self, cp, cp_cam): - # copy can_valid + # copy can_valid on buses 0 and 2 self.can_valid = cp.can_valid + self.cam_can_valid = cp_cam.can_valid # car params - v_weight_v = [0., 1. ] # don't trust smooth speed at low values to avoid premature zero snapping + v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero # update prevs, update must run once per loop @@ -334,152 +190,130 @@ def update(self, cp): self.prev_right_blinker_on = self.right_blinker_on # ******************* parse out can ******************* - self.door_all_closed = not any([cp.vl[0x405]['DOOR_OPEN_FL'], cp.vl[0x405]['DOOR_OPEN_FR'], - cp.vl[0x405]['DOOR_OPEN_RL'], cp.vl[0x405]['DOOR_OPEN_RR']]) - self.seatbelt = not cp.vl[0x305]['SEATBELT_DRIVER_LAMP'] and cp.vl[0x305]['SEATBELT_DRIVER_LATCHED'] - # error 2 = temporary - # error 4 = temporary, hit a bump - # error 5 (permanent) - # error 6 = temporary - # error 7 (permanent) - #self.steer_error = cp.vl[0x18F]['STEER_STATUS'] in [5,7] - # whitelist instead of blacklist, safer at the expense of disengages - if self.accord: - self.steer_error = False - self.steer_not_allowed = False + + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH): # TODO: find wheels moving bit in dbc + self.standstill = cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] < 0.1 + self.door_all_closed = not cp.vl["SCM_FEEDBACK"]['DRIVERS_DOOR_OPEN'] else: - self.steer_error = cp.vl[0x18F]['STEER_STATUS'] not in [0,2,4,6] - self.steer_not_allowed = cp.vl[0x18F]['STEER_STATUS'] != 0 - self.brake_error = cp.vl[0x1B0]['BRAKE_ERROR_1'] or cp.vl[0x1B0]['BRAKE_ERROR_2'] - self.esp_disabled = cp.vl[0x1A4]['ESP_DISABLED'] + self.standstill = not cp.vl["STANDSTILL"]['WHEELS_MOVING'] + self.door_all_closed = not any([cp.vl["DOORS_STATUS"]['DOOR_OPEN_FL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_FR'], + cp.vl["DOORS_STATUS"]['DOOR_OPEN_RL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LAMP'] and cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LATCHED'] + + # 2 = temporary; 3 = TBD; 4 = temporary, hit a bump; 5 = (permanent); 6 = temporary; 7 = (permanent) + # TODO: Use values from DBC to parse this field + self.steer_error = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 2, 3, 4, 6] + self.steer_not_allowed = cp.vl["STEER_STATUS"]['STEER_STATUS'] != 0 + self.steer_warning = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 3] # 3 is low speed lockout, not worth a warning + self.brake_error = cp.vl["STANDSTILL"]['BRAKE_ERROR_1'] or cp.vl["STANDSTILL"]['BRAKE_ERROR_2'] + self.esp_disabled = cp.vl["VSA_STATUS"]['ESP_DISABLED'] + # calc best v_ego estimate, by averaging two opposite corners - self.v_wheel_fl = cp.vl[0x1D0]['WHEEL_SPEED_FL'] - self.v_wheel_fr = cp.vl[0x1D0]['WHEEL_SPEED_FR'] - self.v_wheel_rl = cp.vl[0x1D0]['WHEEL_SPEED_RL'] - self.v_wheel_rr = cp.vl[0x1D0]['WHEEL_SPEED_RR'] - self.v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4. + speed_factor = SPEED_FACTOR[self.CP.carFingerprint] + self.v_wheel_fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS * speed_factor + self.v_wheel_fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS * speed_factor + self.v_wheel_rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS * speed_factor + self.v_wheel_rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS * speed_factor + self.v_wheel = (self.v_wheel_fl+self.v_wheel_fr+self.v_wheel_rl+self.v_wheel_rr)/4. # blend in transmission speed at low speed, since it has more low speed accuracy self.v_weight = interp(self.v_wheel, v_weight_bp, v_weight_v) - speed = (1. - self.v_weight) * cp.vl[0x158]['XMISSION_SPEED'] + self.v_weight * self.v_wheel + speed = (1. - self.v_weight) * cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] * CV.KPH_TO_MS * speed_factor + \ + self.v_weight * self.v_wheel if abs(speed - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed - self.v_ego_x = np.matrix([[speed], [0.0]]) - self.v_ego_x = np.dot((self.v_ego_A - np.dot(self.v_ego_K, self.v_ego_C)), self.v_ego_x) + np.dot(self.v_ego_K, speed) + self.v_ego_x = [[speed], [0.0]] self.v_ego_raw = speed - self.v_ego = float(self.v_ego_x[0]) - self.a_ego = float(self.v_ego_x[1]) - - if self.CP.enableGas: - # this is a hack - self.user_gas = cp.vl[0x201]['INTERCEPTOR_GAS'] + v_ego_x = self.v_ego_kf.update(speed) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + + # this is a hack for the interceptor. This is now only used in the simulation + # TODO: Replace tests by toyota so this can go away + if self.CP.enableGasInterceptor: + self.user_gas = cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS'] self.user_gas_pressed = self.user_gas > 0 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change - #print self.user_gas, self.user_gas_pressed - if self.civic: - can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x14A]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x14A]['STEER_ANGLE_RATE'] - self.gear = 0 # TODO: civic has CVT... needs rev engineering - self.cruise_setting = cp.vl[0x296]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x296]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x326]['MAIN_ON'] - self.blinker_on = cp.vl[0x326]['LEFT_BLINKER'] or cp.vl[0x326]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x326]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x326]['RIGHT_BLINKER'] - self.cruise_speed_offset = calc_cruise_offset(cp.vl[0x37c]['CRUISE_SPEED_OFFSET'], self.v_ego) - self.park_brake = cp.vl[0x1c2]['EPB_STATE'] != 0 - self.brake_hold = cp.vl[0x1A4]['BRAKE_HOLD_ACTIVE'] - elif self.accord: - can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x156]['STEER_ANGLE_RATE'] - self.gear = 0 # TODO: accord has CVT... needs rev engineering - self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - self.cruise_speed_offset = -0.3 - self.park_brake = 0 # TODO - self.brake_hold = 0 # TODO - elif self.crv: - can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x156]['STEER_ANGLE_RATE'] - self.gear = cp.vl[0x191]['GEAR'] - self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - self.cruise_speed_offset = -0.3 + + self.gear = 0 if self.CP.carFingerprint == CAR.CIVIC else cp.vl["GEARBOX"]['GEAR'] + self.angle_steers = cp.vl["STEERING_SENSORS"]['STEER_ANGLE'] + self.angle_steers_rate = cp.vl["STEERING_SENSORS"]['STEER_ANGLE_RATE'] + + self.cruise_setting = cp.vl["SCM_BUTTONS"]['CRUISE_SETTING'] + self.cruise_buttons = cp.vl["SCM_BUTTONS"]['CRUISE_BUTTONS'] + + self.blinker_on = cp.vl["SCM_FEEDBACK"]['LEFT_BLINKER'] or cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] + self.left_blinker_on = cp.vl["SCM_FEEDBACK"]['LEFT_BLINKER'] + self.right_blinker_on = cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] + + if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_HATCH): + self.park_brake = cp.vl["EPB_STATUS"]['EPB_STATE'] != 0 + self.brake_hold = cp.vl["VSA_STATUS"]['BRAKE_HOLD_ACTIVE'] + self.main_on = cp.vl["SCM_FEEDBACK"]['MAIN_ON'] + else: self.park_brake = 0 # TODO self.brake_hold = 0 # TODO - elif self.acura: - can_gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x156]['STEER_ANGLE_RATE'] - self.gear = cp.vl[0x1A3]['GEAR'] - self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - self.cruise_speed_offset = calc_cruise_offset(cp.vl[0x37c]['CRUISE_SPEED_OFFSET'], self.v_ego) - self.park_brake = 0 # TODO - self.brake_hold = 0 - - self.gear_shifter = parse_gear_shifter(can_gear_shifter, self.acura) - - if self.accord: - # on the accord, this doesn't seem to include cruise control - self.car_gas = cp.vl[0x17C]['PEDAL_GAS'] - self.steer_override = False - elif self.crv: - # like accord, crv doesn't include cruise control - self.car_gas = cp.vl[0x17C]['PEDAL_GAS'] - self.steer_override = abs(cp.vl[0x18F]['STEER_TORQUE_SENSOR']) > 1200 + self.main_on = cp.vl["SCM_BUTTONS"]['MAIN_ON'] + + can_gear_shifter = int(cp.vl["GEARBOX"]['GEAR_SHIFTER']) + self.gear_shifter = parse_gear_shifter(can_gear_shifter, self.shifter_values) + + self.pedal_gas = cp.vl["POWERTRAIN_DATA"]['PEDAL_GAS'] + # crv doesn't include cruise control + if self.CP.carFingerprint in (CAR.CRV, CAR.ODYSSEY, CAR.ACURA_RDX, CAR.RIDGELINE, CAR.PILOT_2019): + self.car_gas = self.pedal_gas + else: + self.car_gas = cp.vl["GAS_PEDAL_2"]['CAR_GAS'] + + self.steer_torque_driver = cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR'] + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD[self.CP.carFingerprint] + + self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + + if self.CP.radarOffCan: + self.stopped = cp.vl["ACC_HUD"]['CRUISE_SPEED'] == 252. + self.cruise_speed_offset = calc_cruise_offset(0, self.v_ego) + if self.CP.carFingerprint in (CAR.CIVIC_HATCH, CAR.ACCORDH): + self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + self.brake_pressed = cp.vl["POWERTRAIN_DATA"]['BRAKE_PRESSED'] or \ + (self.brake_switch and self.brake_switch_prev and \ + cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != self.brake_switch_ts) + self.brake_switch_prev = self.brake_switch + self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + else: + self.brake_pressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED'] + # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. + self.v_cruise_pcm = self.v_cruise_pcm_prev if cp.vl["ACC_HUD"]['CRUISE_SPEED'] > 160.0 else cp.vl["ACC_HUD"]['CRUISE_SPEED'] + self.v_cruise_pcm_prev = self.v_cruise_pcm else: - self.car_gas = cp.vl[0x130]['CAR_GAS'] - self.steer_override = abs(cp.vl[0x18F]['STEER_TORQUE_SENSOR']) > 1200 - self.steer_torque_driver = cp.vl[0x18F]['STEER_TORQUE_SENSOR'] - - # brake switch has shown some single time step noise, so only considered when - # switch is on for at least 2 consecutive CAN samples - self.brake_switch = cp.vl[0x17C]['BRAKE_SWITCH'] - self.brake_pressed = cp.vl[0x17C]['BRAKE_PRESSED'] or \ + self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + self.cruise_speed_offset = calc_cruise_offset(cp.vl["CRUISE_PARAMS"]['CRUISE_SPEED_OFFSET'], self.v_ego) + self.v_cruise_pcm = cp.vl["CRUISE"]['CRUISE_SPEED_PCM'] + # brake switch has shown some single time step noise, so only considered when + # switch is on for at least 2 consecutive CAN samples + self.brake_pressed = cp.vl["POWERTRAIN_DATA"]['BRAKE_PRESSED'] or \ (self.brake_switch and self.brake_switch_prev and \ - cp.ts[0x17C]['BRAKE_SWITCH'] != self.brake_switch_ts) - self.brake_switch_prev = self.brake_switch - self.brake_switch_ts = cp.ts[0x17C]['BRAKE_SWITCH'] + cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != self.brake_switch_ts) + self.brake_switch_prev = self.brake_switch + self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] - self.user_brake = cp.vl[0x1A4]['USER_BRAKE'] - self.standstill = not cp.vl[0x1B0]['WHEELS_MOVING'] - self.v_cruise_pcm = cp.vl[0x324]['CRUISE_SPEED_PCM'] - self.pcm_acc_status = cp.vl[0x17C]['ACC_STATUS'] - self.pedal_gas = cp.vl[0x17C]['PEDAL_GAS'] - self.hud_lead = cp.vl[0x30C]['HUD_LEAD'] + self.user_brake = cp.vl["VSA_STATUS"]['USER_BRAKE'] + self.pcm_acc_status = cp.vl["POWERTRAIN_DATA"]['ACC_STATUS'] + self.hud_lead = cp.vl["ACC_HUD"]['HUD_LEAD'] # carstate standalone tester if __name__ == '__main__': import zmq - import time - from selfdrive.services import service_list context = zmq.Context() class CarParams(object): def __init__(self): self.carFingerprint = "HONDA CIVIC 2016 TOURING" - self.enableGas = 0 - self.enableCruise = 0 + self.enableGasInterceptor = 0 CP = CarParams() CS = CarState(CP) - while 1: - CS.update() - time.sleep(0.01) + # while 1: + # CS.update() + # time.sleep(0.01) diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 31615a8cbbe0b2..3d92d24a7c2924 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -1,8 +1,6 @@ import struct - -import common.numpy_fast as np from selfdrive.config import Conversions as CV - +from selfdrive.car.honda.values import CAR, HONDA_BOSCH # *** Honda specific *** def can_cksum(mm): @@ -15,115 +13,100 @@ def can_cksum(mm): s %= 0x10 return s + def fix(msg, addr): msg2 = msg[0:-1] + chr(ord(msg[-1]) | can_cksum(struct.pack("I", addr)+msg)) return msg2 -def make_can_msg(addr, dat, idx, alt): - if idx is not None: - dat += chr(idx << 4) - dat = fix(dat, addr) - return [addr, 0, dat, alt] -def create_brake_command(apply_brake, pcm_override, pcm_cancel_cmd, chime, idx): - """Creates a CAN message for the Honda DBC BRAKE_COMMAND.""" - pump_on = apply_brake > 0 +def create_brake_command(packer, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, chime, fcw, idx): + # TODO: do we loose pressure if we keep pump off for long? brakelights = apply_brake > 0 brake_rq = apply_brake > 0 - pcm_fault_cmd = False - amount = struct.pack("!H", (apply_brake << 6) + pump_on) - msg = amount + struct.pack("BBB", (pcm_override << 4) | - (pcm_fault_cmd << 2) | - (pcm_cancel_cmd << 1) | brake_rq, 0x80, - brakelights << 7) + chr(chime) + "\x00" - return make_can_msg(0x1fa, msg, idx, 0) - -def create_gas_command(gas_amount, idx): - """Creates a CAN message for the Honda DBC GAS_COMMAND.""" - msg = struct.pack("!H", gas_amount) - return make_can_msg(0x200, msg, idx, 0) - -def create_accord_steering_control(apply_steer, idx): - # TODO: doesn't work for some reason - if apply_steer == 0: - dat = [0, 0, 0x40, 0] - else: - dat = [0,0,0,0] - rp = np.clip(apply_steer/0xF, -0xFF, 0xFF) - if rp < 0: - rp += 512 - dat[0] |= (rp >> 5) & 0xf - dat[1] |= (rp) & 0x1f - if idx == 1: - dat[0] |= 0x20 - dat[1] |= 0x20 # always - dat[3] = -(dat[0]+dat[1]+dat[2]) & 0x7f - - # not first byte - dat[1] |= 0x80 - dat[2] |= 0x80 - dat[3] |= 0x80 - dat = ''.join(map(chr, dat)) - - return [0,0,dat,8] - -def create_steering_control(apply_steer, crv, idx): - """Creates a CAN message for the Honda DBC STEERING_CONTROL.""" - commands = [] - if crv: - msg_0x194 = struct.pack("!h", apply_steer << 4) + ("\x80" if apply_steer != 0 else "\x00") - commands.append(make_can_msg(0x194, msg_0x194, idx, 0)) - else: - msg_0xe4 = struct.pack("!h", apply_steer) + ("\x80\x00" if apply_steer != 0 else "\x00\x00") - commands.append(make_can_msg(0xe4, msg_0xe4, idx, 0)) - return commands -def create_ui_commands(pcm_speed, hud, civic, accord, crv, idx): - """Creates an iterable of CAN messages for the UIs.""" - commands = [] - pcm_speed_real = np.clip(int(round(pcm_speed / 0.002759506)), 0, - 64000) # conversion factor from dbc file - msg_0x30c = struct.pack("!HBBBBB", pcm_speed_real, hud.pcm_accel, - hud.v_cruise, hud.X2, hud.car, hud.X4) - commands.append(make_can_msg(0x30c, msg_0x30c, idx, 0)) - - msg_0x33d = chr(hud.X5) + chr(hud.lanes) + chr(hud.beep) + chr(hud.X8) - commands.append(make_can_msg(0x33d, msg_0x33d, idx, 0)) - if civic: # 2 more msgs - msg_0x35e = chr(0) * 7 - commands.append(make_can_msg(0x35e, msg_0x35e, idx, 0)) - if civic or accord: - msg_0x39f = ( - chr(0) * 2 + chr(hud.acc_alert) + chr(0) + chr(0xff) + chr(0x7f) + chr(0) - ) - commands.append(make_can_msg(0x39f, msg_0x39f, idx, 0)) - return commands + values = { + "COMPUTER_BRAKE": apply_brake, + "BRAKE_PUMP_REQUEST": pump_on, + "CRUISE_OVERRIDE": pcm_override, + "CRUISE_FAULT_CMD": pcm_fault_cmd, + "CRUISE_CANCEL_CMD": pcm_cancel_cmd, + "COMPUTER_BRAKE_REQUEST": brake_rq, + "SET_ME_0X80": 0x80, + "BRAKE_LIGHTS": brakelights, + "CHIME": chime, + # TODO: Why are there two bits for fcw? According to dbc file the first bit should also work + "FCW": fcw << 1, + } + return packer.make_can_msg("BRAKE_COMMAND", 0, values, idx) + -def create_radar_commands(v_ego, civic, accord, crv, idx): - """Creates an iterable of CAN messages for the radar system.""" +def create_gas_command(packer, gas_amount, idx): + enable = gas_amount > 0.001 + + values = {"ENABLE": enable} + + if enable: + values["GAS_COMMAND"] = gas_amount * 255. + values["GAS_COMMAND2"] = gas_amount * 255. + + return packer.make_can_msg("GAS_COMMAND", 0, values, idx) + + +def create_steering_control(packer, apply_steer, lkas_active, car_fingerprint, idx): + values = { + "STEER_TORQUE": apply_steer if lkas_active else 0, + "STEER_TORQUE_REQUEST": lkas_active, + } + # Set bus 2 for accord and new crv. + bus = 2 if car_fingerprint in HONDA_BOSCH else 0 + return packer.make_can_msg("STEERING_CONTROL", bus, values, idx) + + +def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, idx): commands = [] - v_ego_kph = np.clip(int(round(v_ego * CV.MS_TO_KPH)), 0, 255) - speed = struct.pack('!B', v_ego_kph) - - msg_0x300 = ("\xf9" + speed + "\x8a\xd0" +\ - ("\x20" if idx == 0 or idx == 3 else "\x00") +\ - "\x00\x00") - if civic: - msg_0x301 = "\x02\x38\x44\x32\x4f\x00\x00" - # add 8 on idx. - commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) - elif accord: - # 0300( 768)( 69) f9008ad0100000ef - # 0301( 769)( 69) 0ed8522256000029 - msg_0x301 = "\x0e\xd8\x52\x22\x56\x00\x00" - # add 0xc on idx? WTF is this? - commands.append(make_can_msg(0x300, msg_0x300, idx + 0xc, 1)) - elif crv: - msg_0x301 = "\x00\x00\x50\x02\x51\x00\x00" - commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) + bus = 0 + + # Bosch sends commands to bus 2. + if car_fingerprint in HONDA_BOSCH: + bus = 2 else: - msg_0x301 = "\x0f\x18\x51\x02\x5a\x00\x00" - commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) - commands.append(make_can_msg(0x301, msg_0x301, idx, 1)) + acc_hud_values = { + 'PCM_SPEED': pcm_speed * CV.MS_TO_KPH, + 'PCM_GAS': hud.pcm_accel, + 'CRUISE_SPEED': hud.v_cruise, + 'ENABLE_MINI_CAR': hud.mini_car, + 'HUD_LEAD': hud.car, + 'SET_ME_X03': 0x03, + 'SET_ME_X03_2': 0x03, + 'SET_ME_X01': 0x01, + } + commands.append(packer.make_can_msg("ACC_HUD", 0, acc_hud_values, idx)) + + lkas_hud_values = { + 'SET_ME_X41': 0x41, + 'SET_ME_X48': 0x48, + 'STEERING_REQUIRED': hud.steer_required, + 'SOLID_LANES': hud.lanes, + 'BEEP': hud.beep, + } + commands.append(packer.make_can_msg('LKAS_HUD', bus, lkas_hud_values, idx)) + + if car_fingerprint in (CAR.CIVIC, CAR.ODYSSEY): + + radar_hud_values = { + 'ACC_ALERTS': hud.acc_alert, + 'LEAD_SPEED': 0x1fe, # What are these magic values + 'LEAD_STATE': 0x7, + 'LEAD_DISTANCE': 0x1e, + } + commands.append(packer.make_can_msg('RADAR_HUD', 0, radar_hud_values, idx)) return commands + + +def spam_buttons_command(packer, button_val, idx): + values = { + 'CRUISE_BUTTONS': button_val, + 'CRUISE_SETTING': 0, + } + return packer.make_can_msg("SCM_BUTTONS", 0, values, idx) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 7879a9ef1e51f4..e074900e59937e 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -1,20 +1,19 @@ #!/usr/bin/env python import os import numpy as np +from cereal import car, log from common.numpy_fast import clip, interp from common.realtime import sec_since_boot +from selfdrive.swaglog import cloudlog from selfdrive.config import Conversions as CV from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET, get_events from selfdrive.controls.lib.vehicle_model import VehicleModel -from cereal import car -from selfdrive.services import service_list -import selfdrive.messaging as messaging -from selfdrive.car.honda.carstate import CarState, get_can_parser -from selfdrive.car.honda.values import CruiseButtons, CM, BP, AH -from selfdrive.controls.lib.planner import A_ACC_MAX +from selfdrive.car.honda.carstate import CarState, get_can_parser, get_cam_can_parser +from selfdrive.car.honda.values import CruiseButtons, CAR, HONDA_BOSCH, AUDIO_HUD, VISUAL_HUD +from selfdrive.controls.lib.planner import _A_CRUISE_MAX_V_FOLLOWING try: - from .carcontroller import CarController + from selfdrive.car.honda.carcontroller import CarController except ImportError: CarController = None @@ -23,6 +22,8 @@ # those messages are mutually exclusive on CRV and non-CRV cars CAMERA_MSGS = [0xe4, 0x194] +A_ACC_MAX = max(_A_CRUISE_MAX_V_FOLLOWING) + def compute_gb_honda(accel, speed): creep_brake = 0.0 @@ -88,8 +89,10 @@ def __init__(self, CP, sendcan=None): self.gas_pressed_prev = False self.brake_pressed_prev = False self.can_invalid_count = 0 + self.cam_can_invalid_count = 0 self.cp = get_can_parser(CP) + self.cp_cam = get_cam_can_parser(CP) # *** init the major players *** self.CS = CarState(CP) @@ -98,19 +101,25 @@ def __init__(self, CP, sendcan=None): # sending if read only is False if sendcan is not None: self.sendcan = sendcan - self.CC = CarController(CP.enableCamera) - - if self.CS.accord: - # self.accord_msg = [] - raise NotImplementedError + self.CC = CarController(self.cp.dbc_name, CP.enableCamera) - if not self.CS.civic: + if self.CS.CP.carFingerprint == CAR.ACURA_ILX: self.compute_gb = get_compute_gb_acura() else: self.compute_gb = compute_gb_honda @staticmethod def calc_accel_override(a_ego, a_target, v_ego, v_target): + + # normalized max accel. Allowing max accel at low speed causes speed overshoots + max_accel_bp = [10, 20] # m/s + max_accel_v = [0.714, 1.0] # unit of max accel + max_accel = interp(v_ego, max_accel_bp, max_accel_v) + + # limit the pcm accel cmd if: + # - v_ego exceeds v_target, or + # - a_ego exceeds a_target and v_ego is close to v_target + eA = a_ego - a_target valuesA = [1.0, 0.1] bpA = [0.3, 1.1] @@ -119,105 +128,212 @@ def calc_accel_override(a_ego, a_target, v_ego, v_target): valuesV = [1.0, 0.1] bpV = [0.0, 0.5] + valuesRangeV = [1., 0.] + bpRangeV = [-1., 0.] + + # only limit if v_ego is close to v_target + speedLimiter = interp(eV, bpV, valuesV) + accelLimiter = max(interp(eA, bpA, valuesA), interp(eV, bpRangeV, valuesRangeV)) + # 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(0.714, a_target / A_ACC_MAX)) * min(interp(eA, bpA, valuesA), interp(eV, bpV, valuesV)) + + return float(max(max_accel, a_target / A_ACC_MAX)) * min(speedLimiter, accelLimiter) @staticmethod def get_params(candidate, fingerprint): - # kg of standard extra cargo to count for drive, gas, etc... - std_cargo = 136 - ret = car.CarParams.new_message() - ret.carName = "honda" - ret.radarName = "nidec" ret.carFingerprint = candidate - ret.safetyModel = car.CarParams.SafetyModels.honda - - ret.enableSteer = True - ret.enableBrake = True + if candidate in HONDA_BOSCH: + ret.safetyModel = car.CarParams.SafetyModels.hondaBosch + ret.enableCamera = True + ret.radarOffCan = True + else: + ret.safetyModel = car.CarParams.SafetyModels.honda + ret.enableCamera = not any(x for x in CAMERA_MSGS if x in fingerprint) + ret.enableGasInterceptor = 0x201 in fingerprint + cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera) + cloudlog.warn("ECU Gas Interceptor: %r", ret.enableGasInterceptor) - ret.enableCamera = not any(x for x in CAMERA_MSGS if x in fingerprint) - ret.enableGas = 0x201 in fingerprint - print "ECU Camera Simulated: ", ret.enableCamera - print "ECU Gas Interceptor: ", ret.enableGas + ret.enableCruise = not ret.enableGasInterceptor - ret.enableCruise = not ret.enableGas + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 # FIXME: hardcoding honda civic 2016 touring params so they can be used to # scale unknown params for other cars - mass_civic = 2923./2.205 + std_cargo + mass_civic = 2923 * CV.LB_TO_KG + std_cargo wheelbase_civic = 2.70 centerToFront_civic = wheelbase_civic * 0.4 centerToRear_civic = wheelbase_civic - centerToFront_civic rotationalInertia_civic = 2500 - tireStiffnessFront_civic = 85400 - tireStiffnessRear_civic = 90000 + tireStiffnessFront_civic = 192150 + tireStiffnessRear_civic = 202500 + + # Optimized car params: tire_stiffness_factor and steerRatio are a result of a vehicle + # model optimization process. 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. + # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" + + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] - if candidate == "HONDA CIVIC 2016 TOURING": + ret.steerKf = 0.00006 # conservative feed-forward + + if candidate == CAR.CIVIC: stop_and_go = True ret.mass = mass_civic ret.wheelbase = wheelbase_civic ret.centerToFront = centerToFront_civic - ret.steerRatio = 13.0 + ret.steerRatio = 14.63 # 10.93 is end-to-end spec + tire_stiffness_factor = 1. # Civic at comma has modified steering FW, so different tuning for the Neo in that car - is_fw_modified = os.getenv("DONGLE_ID") in ['b0f5a01cf604185c'] - ret.steerKp, ret.steerKi = [0.4, 0.12] if is_fw_modified else [0.8, 0.24] - + is_fw_modified = os.getenv("DONGLE_ID") in ['99c94dc769b5d96e'] + ret.steerKpV, ret.steerKiV = [[0.33], [0.10]] if is_fw_modified else [[0.8], [0.24]] + if is_fw_modified: + ret.steerKf = 0.00003 ret.longitudinalKpBP = [0., 5., 35.] ret.longitudinalKpV = [3.6, 2.4, 1.5] ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.54, 0.36] - elif candidate == "ACURA ILX 2016 ACURAWATCH PLUS": + + elif candidate == CAR.CIVIC_HATCH: + stop_and_go = True + ret.mass = 2916. * CV.LB_TO_KG + std_cargo + ret.wheelbase = wheelbase_civic + ret.centerToFront = centerToFront_civic + ret.steerRatio = 14.63 # 10.93 is spec end-to-end + tire_stiffness_factor = 1. + ret.steerKpV, ret.steerKiV = [[0.8], [0.24]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH): + stop_and_go = True + if not candidate == CAR.ACCORDH: # Hybrid uses same brake msg as hatch + ret.safetyParam = 1 # Accord and CRV 5G use an alternate user brake msg + ret.mass = 3279. * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.83 + ret.centerToFront = ret.wheelbase * 0.39 + ret.steerRatio = 15.96 # 11.82 is spec end-to-end + tire_stiffness_factor = 0.8467 + ret.steerKpV, ret.steerKiV = [[0.6], [0.18]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.ACURA_ILX: stop_and_go = False - ret.mass = 3095./2.205 + std_cargo + ret.mass = 3095 * CV.LB_TO_KG + std_cargo ret.wheelbase = 2.67 ret.centerToFront = ret.wheelbase * 0.37 - ret.steerRatio = 15.3 + ret.steerRatio = 18.61 # 15.3 is spec end-to-end + tire_stiffness_factor = 0.72 # Acura at comma has modified steering FW, so different tuning for the Neo in that car - is_fw_modified = os.getenv("DONGLE_ID") in ['cb38263377b873ee'] - ret.steerKp, ret.steerKi = [0.4, 0.12] if is_fw_modified else [0.8, 0.24] + is_fw_modified = os.getenv("DONGLE_ID") in ['ff83f397542ab647'] + ret.steerKpV, ret.steerKiV = [[0.45], [0.00]] if is_fw_modified else [[0.8], [0.24]] + if is_fw_modified: + ret.steerKf = 0.00003 + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.CRV: + stop_and_go = False + ret.mass = 3572 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.62 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 15.3 # as spec + tire_stiffness_factor = 0.444 # not optimized yet + ret.steerKpV, ret.steerKiV = [[0.8], [0.24]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + elif candidate == CAR.CRV_5G: + stop_and_go = True + ret.safetyParam = 1 # Accord and CRV 5G use an alternate user brake msg + ret.mass = 3410. * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.66 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 16.0 # 12.3 is spec end-to-end + tire_stiffness_factor = 0.677 + ret.steerKpV, ret.steerKiV = [[0.6], [0.18]] ret.longitudinalKpBP = [0., 5., 35.] ret.longitudinalKpV = [1.2, 0.8, 0.5] ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.18, 0.12] - elif candidate == "HONDA ACCORD 2016 TOURING": + + elif candidate == CAR.ACURA_RDX: stop_and_go = False - ret.mass = 3580./2.205 + std_cargo - ret.wheelbase = 2.74 + ret.mass = 3935 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.68 ret.centerToFront = ret.wheelbase * 0.38 - ret.steerRatio = 15.3 - ret.steerKp, ret.steerKi = 0.8, 0.24 + ret.steerRatio = 15.0 # as spec + tire_stiffness_factor = 0.444 # not optimized yet + ret.steerKpV, ret.steerKiV = [[0.8], [0.24]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + elif candidate == CAR.ODYSSEY: + stop_and_go = False + ret.mass = 4471 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 3.00 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 14.35 # as spec + tire_stiffness_factor = 0.82 + ret.steerKpV, ret.steerKiV = [[0.45], [0.135]] ret.longitudinalKpBP = [0., 5., 35.] ret.longitudinalKpV = [1.2, 0.8, 0.5] ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.18, 0.12] - elif candidate == "HONDA CR-V 2016 TOURING": + + elif candidate in (CAR.PILOT, CAR.PILOT_2019): stop_and_go = False - ret.mass = 3572./2.205 + std_cargo - ret.wheelbase = 2.62 + ret.mass = 4303 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.81 ret.centerToFront = ret.wheelbase * 0.41 - ret.steerRatio = 15.3 - ret.steerKp, ret.steerKi = 0.8, 0.24 + ret.steerRatio = 16.0 # as spec + tire_stiffness_factor = 0.444 # not optimized yet + ret.steerKpV, ret.steerKiV = [[0.38], [0.11]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + elif candidate == CAR.RIDGELINE: + stop_and_go = False + ret.mass = 4515 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 3.18 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 15.59 # as spec + tire_stiffness_factor = 0.444 # not optimized yet + ret.steerKpV, ret.steerKiV = [[0.38], [0.11]] ret.longitudinalKpBP = [0., 5., 35.] ret.longitudinalKpV = [1.2, 0.8, 0.5] ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.18, 0.12] + else: raise ValueError("unsupported car %s" % candidate) - ret.steerKf = 0. # TODO: investigate FF steer control for Honda + ret.steerControlType = car.CarParams.SteerControlType.torque # 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 # conflict with PCM acc - ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGas) else 25.5 * CV.MPH_TO_MS + ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else 25.5 * CV.MPH_TO_MS centerToRear = ret.wheelbase - ret.centerToFront # TODO: get actual value, for now starting with reasonable value for @@ -227,10 +343,10 @@ def get_params(candidate, fingerprint): # TODO: start from empirically derived lateral slip stiffness for the civic and scale by # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront = tireStiffnessFront_civic * \ + ret.tireStiffnessFront = (tireStiffnessFront_civic * tire_stiffness_factor) * \ ret.mass / mass_civic * \ (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) - ret.tireStiffnessRear = tireStiffnessRear_civic * \ + ret.tireStiffnessRear = (tireStiffnessRear_civic * tire_stiffness_factor) * \ ret.mass / mass_civic * \ (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) @@ -242,7 +358,7 @@ def get_params(candidate, fingerprint): ret.steerMaxV = [1.] # max steer allowed ret.gasMaxBP = [0.] # m/s - ret.gasMaxV = [0.6] if ret.enableGas else [0.] # max gas allowed + 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 @@ -253,6 +369,7 @@ def get_params(candidate, fingerprint): ret.steerLimitAlert = True ret.startAccel = 0.5 + ret.steerActuatorDelay = 0.1 ret.steerRateCost = 0.5 return ret @@ -263,8 +380,9 @@ def update(self, c): canMonoTimes = [] self.cp.update(int(sec_since_boot() * 1e9), False) + self.cp_cam.update(int(sec_since_boot() * 1e9), False) - self.CS.update(self.cp) + self.CS.update(self.cp, self.cp_cam) # create message ret = car.CarState.new_message() @@ -282,7 +400,7 @@ def update(self, c): # gas pedal ret.gas = self.CS.car_gas / 256.0 - if not self.CP.enableGas: + if not self.CP.enableGasInterceptor: ret.gasPressed = self.CS.pedal_gas > 0 else: ret.gasPressed = self.CS.user_gas_pressed @@ -291,7 +409,7 @@ def update(self, c): ret.brake = self.CS.user_brake ret.brakePressed = self.CS.brake_pressed != 0 # FIXME: read sendcan for brakelights - brakelights_threshold = 0.02 if self.CS.civic else 0.1 + brakelights_threshold = 0.02 if self.CS.CP.carFingerprint == CAR.CIVIC else 0.1 ret.brakeLights = bool(self.CS.brake_switch or c.actuators.brake > brakelights_threshold) @@ -317,6 +435,9 @@ def update(self, c): ret.leftBlinker = bool(self.CS.left_blinker_on) ret.rightBlinker = bool(self.CS.right_blinker_on) + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: be = car.CarState.ButtonEvent.new_message() be.type = 'leftBlinker' @@ -373,17 +494,26 @@ def update(self, c): events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) else: self.can_invalid_count = 0 + + if not self.CS.cam_can_valid and self.CP.enableCamera: + self.cam_can_invalid_count += 1 + # wait 1.0s before throwing the alert to avoid it popping when you turn off the car + if self.cam_can_invalid_count >= 100 and self.CS.CP.carFingerprint not in HONDA_BOSCH: + events.append(create_event('invalidGiraffeHonda', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + else: + self.cam_can_invalid_count = 0 + if self.CS.steer_error: events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) - elif self.CS.steer_not_allowed: - events.append(create_event('steerTempUnavailable', [ET.NO_ENTRY, ET.WARNING])) + elif self.CS.steer_warning: + events.append(create_event('steerTempUnavailable', [ET.WARNING])) if self.CS.brake_error: events.append(create_event('brakeUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) if not ret.gearShifter == 'drive': events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.door_all_closed: + if ret.doorOpen: events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.seatbelt: + if ret.seatbeltUnlatched: events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if self.CS.esp_disabled: events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) @@ -391,7 +521,7 @@ def update(self, c): events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) if ret.gearShifter == 'reverse': events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) - if self.CS.brake_hold: + if self.CS.brake_hold and self.CS.CP.carFingerprint not in HONDA_BOSCH: events.append(create_event('brakeHold', [ET.NO_ENTRY, ET.USER_DISABLE])) if self.CS.park_brake: events.append(create_event('parkBrake', [ET.NO_ENTRY, ET.USER_DISABLE])) @@ -409,10 +539,13 @@ def update(self, c): # 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 - # TODO: for the Acura, cancellation below 25mph is normal. Issue a non loud alert if self.CP.enableCruise and not ret.cruiseState.enabled and c.actuators.brake <= 0.: - events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE])) - if not self.CS.civic and ret.vEgo < 0.001: + # non loud alert if cruise disbales below 25mph as expected (+ a little margin) + if ret.vEgo < self.CP.minEnableSpeed + 2.: + events.append(create_event('speedTooLow', [ET.IMMEDIATE_DISABLE])) + else: + events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE])) + if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: events.append(create_event('manualRestart', [ET.WARNING])) cur_time = sec_since_boot() @@ -422,7 +555,6 @@ def update(self, c): # do enable on both accel and decel buttons if b.type in ["accelCruise", "decelCruise"] and not b.pressed: - print "enabled pressed at", cur_time self.last_enable_pressed = cur_time enable_pressed = True @@ -456,30 +588,14 @@ def update(self, c): # pass in a car.CarControl # to be called @ 100hz - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): if c.hudControl.speedVisible: hud_v_cruise = c.hudControl.setSpeed * CV.MS_TO_KPH else: hud_v_cruise = 255 - hud_alert = { - "none": AH.NONE, - "fcw": AH.FCW, - "steerRequired": AH.STEER, - "brakePressed": AH.BRAKE_PRESSED, - "wrongGear": AH.GEAR_NOT_D, - "seatbeltUnbuckled": AH.SEATBELT, - "speedTooHigh": AH.SPEED_TOO_HIGH}[str(c.hudControl.visualAlert)] - - snd_beep, snd_chime = { - "none": (BP.MUTE, CM.MUTE), - "beepSingle": (BP.SINGLE, CM.MUTE), - "beepTriple": (BP.TRIPLE, CM.MUTE), - "beepRepeated": (BP.REPEATED, CM.MUTE), - "chimeSingle": (BP.MUTE, CM.SINGLE), - "chimeDouble": (BP.MUTE, CM.DOUBLE), - "chimeRepeated": (BP.MUTE, CM.REPEATED), - "chimeContinuous": (BP.MUTE, CM.CONTINUOUS)}[str(c.hudControl.audibleAlert)] + hud_alert = VISUAL_HUD[c.hudControl.visualAlert.raw] + snd_beep, snd_chime = AUDIO_HUD[c.hudControl.audibleAlert.raw] pcm_accel = int(clip(c.cruiseControl.accelOverride,0,1)*0xc6) @@ -489,6 +605,7 @@ def apply(self, c): c.cruiseControl.override, \ c.cruiseControl.cancel, \ pcm_accel, \ + perception_state.radarErrors, \ hud_v_cruise, c.hudControl.lanesVisible, \ hud_show_car = c.hudControl.leadVisible, \ hud_alert = hud_alert, \ diff --git a/selfdrive/radar/nidec/interface.py b/selfdrive/car/honda/radar_interface.py similarity index 82% rename from selfdrive/radar/nidec/interface.py rename to selfdrive/car/honda/radar_interface.py index fb2a68693711f7..7d30265c2f471e 100755 --- a/selfdrive/radar/nidec/interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -1,13 +1,10 @@ #!/usr/bin/env python import os -import numpy as np - -from selfdrive.can.parser import CANParser - +import zmq +import time from cereal import car +from selfdrive.can.parser import CANParser from common.realtime import sec_since_boot - -import zmq from selfdrive.services import service_list import selfdrive.messaging as messaging @@ -26,11 +23,13 @@ def _create_nidec_can_parser(): class RadarInterface(object): - def __init__(self): + def __init__(self, CP): # radar self.pts = {} self.track_id = 0 self.radar_fault = False + self.radar_wrong_config = False + self.radar_off_can = CP.radarOffCan self.delay = 0.1 # Delay of radar @@ -44,6 +43,14 @@ def update(self): canMonoTimes = [] updated_messages = set() + ret = car.RadarState.new_message() + + # in Bosch radar and we are only steering for now, so sleep 0.05s to keep + # radard at 20Hz and return no points + if self.radar_off_can: + time.sleep(0.05) + return ret + while 1: tm = int(sec_since_boot() * 1e9) updated_messages.update(self.rcp.update(tm, True)) @@ -55,6 +62,7 @@ def update(self): if ii == 0x400: # check for radar faults self.radar_fault = cpt['RADAR_STATE'] != 0x79 + self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 elif cpt['LONG_DIST'] < 255: if ii not in self.pts or cpt['NEW_TRACK']: self.pts[ii] = car.RadarState.RadarPoint.new_message() @@ -70,21 +78,26 @@ def update(self): if ii in self.pts: del self.pts[ii] - ret = car.RadarState.new_message() errors = [] if not self.rcp.can_valid: errors.append("commIssue") if self.radar_fault: errors.append("fault") + if self.radar_wrong_config: + errors.append("wrongConfig") ret.errors = errors ret.canMonoTimes = canMonoTimes ret.points = self.pts.values() + return ret if __name__ == "__main__": - RI = RadarInterface() + class CarParams: + radarOffCan = False + + RI = RadarInterface(CarParams) while 1: ret = RI.update() print(chr(27) + "[2J") diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index ee5c08884b3f79..17492eaf08ad96 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -1,3 +1,9 @@ +from cereal import car +from selfdrive.car import dbc_dict + +AudibleAlert = car.CarControl.HUDControl.AudibleAlert +VisualAlert = car.CarControl.HUDControl.VisualAlert + # Car button codes class CruiseButtons: RES_ACCEL = 4 @@ -5,7 +11,6 @@ class CruiseButtons: CANCEL = 2 MAIN = 1 - #car chimes: enumeration from dbc file. Chimes are for alerts and warnings class CM: MUTE = 0 @@ -14,21 +19,155 @@ class CM: REPEATED = 1 CONTINUOUS = 2 - -#car beepss: enumeration from dbc file. Beeps are for activ and deactiv +#car beeps: enumeration from dbc file. Beeps are for engage and disengage class BP: MUTE = 0 SINGLE = 3 TRIPLE = 2 REPEATED = 1 +AUDIO_HUD = { + AudibleAlert.none: (BP.MUTE, CM.MUTE), + AudibleAlert.chimeEngage: (BP.SINGLE, CM.MUTE), + AudibleAlert.chimeDisengage: (BP.SINGLE, CM.MUTE), + AudibleAlert.chimeError: (BP.MUTE, CM.DOUBLE), + AudibleAlert.chimePrompt: (BP.MUTE, CM.SINGLE), + AudibleAlert.chimeWarning1: (BP.MUTE, CM.DOUBLE), + AudibleAlert.chimeWarning2: (BP.MUTE, CM.REPEATED), + AudibleAlert.chimeWarningRepeat: (BP.MUTE, CM.REPEATED)} + class AH: #[alert_idx, value] # See dbc files for info on values" NONE = [0, 0] - FCW = [1, 0x8] + FCW = [1, 1] STEER = [2, 1] BRAKE_PRESSED = [3, 10] GEAR_NOT_D = [4, 6] SEATBELT = [5, 5] SPEED_TOO_HIGH = [6, 8] + +VISUAL_HUD = { + VisualAlert.none: AH.NONE, + VisualAlert.fcw: AH.FCW, + VisualAlert.steerRequired: AH.STEER, + VisualAlert.brakePressed: AH.BRAKE_PRESSED, + VisualAlert.wrongGear: AH.GEAR_NOT_D, + VisualAlert.seatbeltUnbuckled: AH.SEATBELT, + VisualAlert.speedTooHigh: AH.SPEED_TOO_HIGH} + +class CAR: + ACCORD = "HONDA ACCORD 2018 SPORT 2T" + ACCORD_15 = "HONDA ACCORD 2018 LX 1.5T" + ACCORDH = "HONDA ACCORD 2018 HYBRID TOURING" + CIVIC = "HONDA CIVIC 2016 TOURING" + CIVIC_HATCH = "HONDA CIVIC HATCHBACK 2017 EX" + ACURA_ILX = "ACURA ILX 2016 ACURAWATCH PLUS" + CRV = "HONDA CR-V 2016 TOURING" + CRV_5G = "HONDA CR-V 2017 EX" + ODYSSEY = "HONDA ODYSSEY 2018 EX-L" + ACURA_RDX = "ACURA RDX 2018 ACURAWATCH PLUS" + PILOT = "HONDA PILOT 2017 TOURING" + PILOT_2019 = "HONDA PILOT 2019 ELITE" + RIDGELINE = "HONDA RIDGELINE 2017 BLACK EDITION" + +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.ACCORD_15: [{ + 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 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 + }], + CAR.CIVIC: [{ + 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 428: 8, 432: 7, 450: 8, 464: 8, 470: 2, 476: 7, 487: 4, 490: 8, 493: 5, 506: 8, 512: 6, 513: 6, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 892: 8, 927: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1633: 8, + }], + CAR.CIVIC_HATCH: [{ + 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 428: 8, 432: 7, 441: 5, 450: 8, 464: 8, 470: 2, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 506: 8, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 892: 8, 927: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1633: 8 + }], + CAR.CRV: [{ + 57: 3, 145: 8, 316: 8, 340: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 6, 401: 8, 404: 4, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 493: 3, 506: 8, 507: 1, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 661: 4, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 829: 5, 882: 2, 884: 7, 888: 8, 891: 8, 892: 8, 923: 2, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1033: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 1424: 5, 1600: 5, 1601: 8, + }], + 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: 4, 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 + }], + # 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 + }, + # 2018 Odyssey Elite w/ Added Comma Pedal Support (512L & 513L) + { + 57: 3, 148: 8, 228: 5, 229: 4, 304: 8, 342: 6, 344: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 427: 3, 432: 7, 440: 8, 450: 8, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 507: 1, 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, 1616: 5, 1619: 5, 1623: 5, 1668: 5 + }], + # 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 + }], + CAR.PILOT_2019: [{ + 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 392: 6, 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, 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, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 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 + }], + # Ridgeline w/ Added Comma Pedal Support (512L & 513L) + CAR.RIDGELINE: [{ + 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 471: 3, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 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, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 927: 8, 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, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1613: 5, 1616: 5, 1618: 5, 1668: 5, 2015: 3 + }] +} + +DBC = { + CAR.ACCORD: dbc_dict('honda_accord_s2t_2018_can_generated', None), + CAR.ACCORD_15: dbc_dict('honda_accord_lx15t_2018_can_generated', None), + CAR.ACCORDH: dbc_dict('honda_accord_s2t_2018_can_generated', None), + CAR.ACURA_ILX: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.ACURA_RDX: dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), + CAR.CIVIC: dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.CIVIC_HATCH: dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), + CAR.CRV: dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.CRV_5G: dbc_dict('honda_crv_ex_2017_can_generated', None), + CAR.ODYSSEY: dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), + CAR.PILOT: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'), + CAR.PILOT_2019: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'), + CAR.RIDGELINE: dbc_dict('honda_ridgeline_black_edition_2017_can_generated', 'acura_ilx_2016_nidec'), +} + +STEER_THRESHOLD = { + CAR.ACCORD: 1200, + CAR.ACCORD_15: 1200, + CAR.ACCORDH: 1200, + CAR.ACURA_ILX: 1200, + CAR.ACURA_RDX: 400, + CAR.CIVIC: 1200, + CAR.CIVIC_HATCH: 1200, + CAR.CRV: 1200, + CAR.CRV_5G: 1200, + CAR.ODYSSEY: 1200, + CAR.PILOT: 1200, + CAR.PILOT_2019: 1200, + CAR.RIDGELINE: 1200, +} + +SPEED_FACTOR = { + CAR.ACCORD: 1., + CAR.ACCORD_15: 1., + CAR.ACCORDH: 1., + CAR.ACURA_ILX: 1., + CAR.ACURA_RDX: 1., + CAR.CIVIC: 1., + CAR.CIVIC_HATCH: 1., + CAR.CRV: 1.025, + CAR.CRV_5G: 1.025, + CAR.ODYSSEY: 1., + CAR.PILOT: 1., + CAR.PILOT_2019: 1., + CAR.RIDGELINE: 1., +} + +# TODO: get these from dbc file +HONDA_BOSCH = [CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_HATCH, CAR.CRV_5G] diff --git a/selfdrive/car/hyundai/__init__.py b/selfdrive/car/hyundai/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py new file mode 100644 index 00000000000000..3cd8d136ff8a27 --- /dev/null +++ b/selfdrive/car/hyundai/carcontroller.py @@ -0,0 +1,76 @@ +from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.car.hyundai.hyundaican import create_lkas11, create_lkas12, \ + create_1191, create_1156, \ + create_clu11 +from selfdrive.car.hyundai.values import Buttons +from selfdrive.can.packer import CANPacker + + +# Steer torque limits + +class SteerLimitParams: + STEER_MAX = 250 # 409 is the max + STEER_DELTA_UP = 3 + STEER_DELTA_DOWN = 7 + STEER_DRIVER_ALLOWANCE = 50 + STEER_DRIVER_MULTIPLIER = 2 + STEER_DRIVER_FACTOR = 1 + +class CarController(object): + def __init__(self, dbc_name, car_fingerprint, enable_camera): + self.apply_steer_last = 0 + self.car_fingerprint = car_fingerprint + self.lkas11_cnt = 0 + self.cnt = 0 + self.last_resume_cnt = 0 + self.enable_camera = enable_camera + # True when giraffe switch 2 is low and we need to replace all the camera messages + # otherwise we forward the camera msgs and we just replace the lkas cmd signals + self.camera_disconnected = False + + self.packer = CANPacker(dbc_name) + + def update(self, sendcan, enabled, CS, actuators, pcm_cancel_cmd, hud_alert): + + if not self.enable_camera: + return + + ### Steering Torque + apply_steer = actuators.steer * SteerLimitParams.STEER_MAX + + apply_steer = apply_std_steer_torque_limits(apply_steer, self.apply_steer_last, CS.steer_torque_driver, SteerLimitParams) + + if not enabled: + apply_steer = 0 + + steer_req = 1 if enabled else 0 + + self.apply_steer_last = apply_steer + + can_sends = [] + + self.lkas11_cnt = self.cnt % 0x10 + self.clu11_cnt = self.cnt % 0x10 + + if self.camera_disconnected: + if (self.cnt % 10) == 0: + can_sends.append(create_lkas12()) + if (self.cnt % 50) == 0: + can_sends.append(create_1191()) + if (self.cnt % 7) == 0: + can_sends.append(create_1156()) + + can_sends.append(create_lkas11(self.packer, self.car_fingerprint, apply_steer, steer_req, self.lkas11_cnt, + enabled, CS.lkas11, hud_alert, keep_stock=(not self.camera_disconnected))) + + if pcm_cancel_cmd: + can_sends.append(create_clu11(self.packer, CS.clu11, Buttons.CANCEL)) + elif CS.stopped and (self.cnt - self.last_resume_cnt) > 5: + self.last_resume_cnt = self.cnt + can_sends.append(create_clu11(self.packer, CS.clu11, Buttons.RES_ACCEL)) + + ### Send messages to canbus + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) + + self.cnt += 1 diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py new file mode 100644 index 00000000000000..451183802085e0 --- /dev/null +++ b/selfdrive/car/hyundai/carstate.py @@ -0,0 +1,239 @@ +from selfdrive.car.hyundai.values import DBC +from selfdrive.can.parser import CANParser +from selfdrive.config import Conversions as CV +from common.kalman.simple_kalman import KF1D +import numpy as np + + +def get_can_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("WHL_SPD_FL", "WHL_SPD11", 0), + ("WHL_SPD_FR", "WHL_SPD11", 0), + ("WHL_SPD_RL", "WHL_SPD11", 0), + ("WHL_SPD_RR", "WHL_SPD11", 0), + + ("YAW_RATE", "ESP12", 0), + + ("CF_Gway_DrvSeatBeltInd", "CGW4", 1), + + ("CF_Gway_DrvSeatBeltSw", "CGW1", 0), + ("CF_Gway_TSigLHSw", "CGW1", 0), + ("CF_Gway_TurnSigLh", "CGW1", 0), + ("CF_Gway_TSigRHSw", "CGW1", 0), + ("CF_Gway_TurnSigRh", "CGW1", 0), + ("CF_Gway_ParkBrakeSw", "CGW1", 0), + + ("BRAKE_ACT", "EMS12", 0), + ("PV_AV_CAN", "EMS12", 0), + ("TPS", "EMS12", 0), + + ("CYL_PRES", "ESP12", 0), + + ("CF_Clu_CruiseSwState", "CLU11", 0), + ("CF_Clu_CruiseSwMain" , "CLU11", 0), + ("CF_Clu_SldMainSW", "CLU11", 0), + ("CF_Clu_ParityBit1", "CLU11", 0), + ("CF_Clu_VanzDecimal" , "CLU11", 0), + ("CF_Clu_Vanz", "CLU11", 0), + ("CF_Clu_SPEED_UNIT", "CLU11", 0), + ("CF_Clu_DetentOut", "CLU11", 0), + ("CF_Clu_RheostatLevel", "CLU11", 0), + ("CF_Clu_CluInfo", "CLU11", 0), + ("CF_Clu_AmpInfo", "CLU11", 0), + ("CF_Clu_AliveCnt1", "CLU11", 0), + + ("CF_Clu_InhibitD", "CLU15", 0), + ("CF_Clu_InhibitP", "CLU15", 0), + ("CF_Clu_InhibitN", "CLU15", 0), + ("CF_Clu_InhibitR", "CLU15", 0), + + ("CF_Lvr_Gear","LVR12",0), + + ("ACCEnable", "TCS13", 0), + ("ACC_REQ", "TCS13", 0), + ("DriverBraking", "TCS13", 0), + ("DriverOverride", "TCS13", 0), + + ("ESC_Off_Step", "TCS15", 0), + + ("CF_Lvr_GearInf", "LVR11", 0), #Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) + + ("CR_Mdps_DrvTq", "MDPS11", 0), + + ("CR_Mdps_StrColTq", "MDPS12", 0), + ("CF_Mdps_ToiActive", "MDPS12", 0), + ("CF_Mdps_ToiUnavail", "MDPS12", 0), + ("CF_Mdps_FailStat", "MDPS12", 0), + ("CR_Mdps_OutTq", "MDPS12", 0), + + ("VSetDis", "SCC11", 0), + ("SCCInfoDisplay", "SCC11", 0), + ("ACCMode", "SCC12", 1), + + ("SAS_Angle", "SAS11", 0), + ("SAS_Speed", "SAS11", 0), + ] + + checks = [ + # address, frequency + ("MDPS12", 50), + ("MDPS11", 100), + ("TCS15", 10), + ("TCS13", 50), + ("CLU11", 50), + ("ESP12", 100), + ("EMS12", 100), + ("CGW1", 10), + ("CGW4", 5), + ("WHL_SPD11", 50), + ("SCC11", 50), + ("SCC12", 50), + ("SAS11", 100) + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + +def get_camera_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("CF_Lkas_LdwsSysState", "LKAS11", 0), + ("CF_Lkas_SysWarning", "LKAS11", 0), + ("CF_Lkas_LdwsLHWarning", "LKAS11", 0), + ("CF_Lkas_LdwsRHWarning", "LKAS11", 0), + ("CF_Lkas_HbaLamp", "LKAS11", 0), + ("CF_Lkas_FcwBasReq", "LKAS11", 0), + ("CF_Lkas_ToiFlt", "LKAS11", 0), + ("CF_Lkas_HbaSysState", "LKAS11", 0), + ("CF_Lkas_FcwOpt", "LKAS11", 0), + ("CF_Lkas_HbaOpt", "LKAS11", 0), + ("CF_Lkas_FcwSysState", "LKAS11", 0), + ("CF_Lkas_FcwCollisionWarning", "LKAS11", 0), + ("CF_Lkas_FusionState", "LKAS11", 0), + ("CF_Lkas_FcwOpt_USM", "LKAS11", 0), + ("CF_Lkas_LdwsOpt_USM", "LKAS11", 0) + ] + + checks = [] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) + +class CarState(object): + def __init__(self, CP): + + self.CP = CP + + # initialize can parser + self.car_fingerprint = CP.carFingerprint + + # vEgo kalman filter + dt = 0.01 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0.0 + self.left_blinker_on = 0 + self.left_blinker_flash = 0 + self.right_blinker_on = 0 + self.right_blinker_flash = 0 + + def update(self, cp, cp_cam): + # copy can_valid + self.can_valid = cp.can_valid + + # update prevs, update must run once per Loop + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + + self.door_all_closed = True + self.seatbelt = cp.vl["CGW1"]['CF_Gway_DrvSeatBeltSw'] + + self.brake_pressed = cp.vl["TCS13"]['DriverBraking'] + self.esp_disabled = cp.vl["TCS15"]['ESC_Off_Step'] + + self.park_brake = cp.vl["CGW1"]['CF_Gway_ParkBrakeSw'] + self.main_on = True + self.acc_active = cp.vl["SCC12"]['ACCMode'] != 0 + self.pcm_acc_status = int(self.acc_active) + + # calc best v_ego estimate, by averaging two opposite corners + self.v_wheel_fl = cp.vl["WHL_SPD11"]['WHL_SPD_FL'] * CV.KPH_TO_MS + self.v_wheel_fr = cp.vl["WHL_SPD11"]['WHL_SPD_FR'] * CV.KPH_TO_MS + self.v_wheel_rl = cp.vl["WHL_SPD11"]['WHL_SPD_RL'] * CV.KPH_TO_MS + self.v_wheel_rr = cp.vl["WHL_SPD11"]['WHL_SPD_RR'] * CV.KPH_TO_MS + self.v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4. + + self.low_speed_lockout = self.v_wheel < 1.0 + + # Kalman filter, even though Hyundai raw wheel speed is heaviliy filtered by default + if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) + + self.v_ego_raw = self.v_wheel + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + is_set_speed_in_mph = int(cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"]) + speed_conv = CV.MPH_TO_MS if is_set_speed_in_mph else CV.KPH_TO_MS + self.cruise_set_speed = cp.vl["SCC11"]['VSetDis'] * speed_conv + self.standstill = not self.v_wheel > 0.1 + + self.angle_steers = cp.vl["SAS11"]['SAS_Angle'] + self.angle_steers_rate = cp.vl["SAS11"]['SAS_Speed'] + self.yaw_rate = cp.vl["ESP12"]['YAW_RATE'] + self.main_on = True + self.left_blinker_on = cp.vl["CGW1"]['CF_Gway_TSigLHSw'] + self.left_blinker_flash = cp.vl["CGW1"]['CF_Gway_TurnSigLh'] + self.right_blinker_on = cp.vl["CGW1"]['CF_Gway_TSigRHSw'] + self.right_blinker_flash = cp.vl["CGW1"]['CF_Gway_TurnSigRh'] + self.steer_override = abs(cp.vl["MDPS11"]['CR_Mdps_DrvTq']) > 100. + self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] #0 NOT ACTIVE, 1 ACTIVE + self.steer_error = cp.vl["MDPS12"]['CF_Mdps_ToiUnavail'] + self.brake_error = 0 + self.steer_torque_driver = cp.vl["MDPS11"]['CR_Mdps_DrvTq'] + self.steer_torque_motor = cp.vl["MDPS12"]['CR_Mdps_OutTq'] + self.stopped = cp.vl["SCC11"]['SCCInfoDisplay'] == 4. + + self.user_brake = 0 + + self.brake_pressed = cp.vl["TCS13"]['DriverBraking'] + self.brake_lights = bool(self.brake_pressed) + if (cp.vl["TCS13"]["DriverOverride"] == 0 and cp.vl["TCS13"]['ACC_REQ'] == 1): + self.pedal_gas = 0 + else: + self.pedal_gas = cp.vl["EMS12"]['TPS'] + self.car_gas = cp.vl["EMS12"]['TPS'] + + # Gear Selecton - This is not compatible with all Kia/Hyundai's, But is the best way for those it is compatible with + gear = cp.vl["LVR12"]["CF_Lvr_Gear"] + if gear == 5: + self.gear_shifter = "drive" + elif gear == 6: + self.gear_shifter = "neutral" + elif gear == 0: + self.gear_shifter = "park" + elif gear == 7: + self.gear_shifter = "reverse" + else: + self.gear_shifter = "unknown" + + # 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 cp.vl["CLU15"]["CF_Clu_InhibitD"] == 1: + self.gear_shifter_cluster = "drive" + elif cp.vl["CLU15"]["CF_Clu_InhibitN"] == 1: + self.gear_shifter_cluster = "neutral" + elif cp.vl["CLU15"]["CF_Clu_InhibitP"] == 1: + self.gear_shifter_cluster = "park" + elif cp.vl["CLU15"]["CF_Clu_InhibitR"] == 1: + self.gear_shifter_cluster = "reverse" + else: + self.gear_shifter_cluster = "unknown" + + # save the entire LKAS11 and CLU11 + self.lkas11 = cp_cam.vl["LKAS11"] + self.clu11 = cp.vl["CLU11"] diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py new file mode 100644 index 00000000000000..5a895497a1865f --- /dev/null +++ b/selfdrive/car/hyundai/hyundaican.py @@ -0,0 +1,79 @@ +import crcmod +from selfdrive.car.hyundai.values import CHECKSUM + +hyundai_checksum = crcmod.mkCrcFun(0x11D, initCrc=0xFD, rev=False, xorOut=0xdf) + +def make_can_msg(addr, dat, alt): + return [addr, 0, dat, alt] + +def create_lkas11(packer, car_fingerprint, apply_steer, steer_req, cnt, enabled, lkas11, hud_alert, keep_stock=False): + values = { + "CF_Lkas_Icon": 3 if enabled else 0, + "CF_Lkas_LdwsSysState": 3 if steer_req else 1, + "CF_Lkas_SysWarning": hud_alert, + "CF_Lkas_LdwsLHWarning": lkas11["CF_Lkas_LdwsLHWarning"] if keep_stock else 0, + "CF_Lkas_LdwsRHWarning": lkas11["CF_Lkas_LdwsRHWarning"] if keep_stock else 0, + "CF_Lkas_HbaLamp": lkas11["CF_Lkas_HbaLamp"] if keep_stock else 0, + "CF_Lkas_FcwBasReq": lkas11["CF_Lkas_FcwBasReq"] if keep_stock else 0, + "CR_Lkas_StrToqReq": apply_steer, + "CF_Lkas_ActToi": steer_req, + "CF_Lkas_ToiFlt": 0, + "CF_Lkas_HbaSysState": lkas11["CF_Lkas_HbaSysState"] if keep_stock else 1, + "CF_Lkas_FcwOpt": lkas11["CF_Lkas_FcwOpt"] if keep_stock else 0, + "CF_Lkas_HbaOpt": lkas11["CF_Lkas_HbaOpt"] if keep_stock else 3, + "CF_Lkas_MsgCount": cnt, + "CF_Lkas_FcwSysState": lkas11["CF_Lkas_FcwSysState"] if keep_stock else 0, + "CF_Lkas_FcwCollisionWarning": lkas11["CF_Lkas_FcwCollisionWarning"] if keep_stock else 0, + "CF_Lkas_FusionState": lkas11["CF_Lkas_FusionState"] if keep_stock else 0, + "CF_Lkas_Chksum": 0, + "CF_Lkas_FcwOpt_USM": 2 if enabled else 1, + "CF_Lkas_LdwsOpt_USM": lkas11["CF_Lkas_LdwsOpt_USM"] if keep_stock else 3, + } + + dat = packer.make_can_msg("LKAS11", 0, values)[2] + + if car_fingerprint in CHECKSUM["crc8"]: + # CRC Checksum as seen on 2019 Hyundai Santa Fe + dat = dat[:6] + dat[7] + checksum = hyundai_checksum(dat) + elif car_fingerprint in CHECKSUM["6B"]: + # Checksum of first 6 Bytes, as seen on 2018 Kia Sorento + dat = [ord(i) for i in dat] + checksum = sum(dat[:6]) % 256 + elif car_fingerprint in CHECKSUM["7B"]: + # Checksum of first 6 Bytes and last Byte as seen on 2018 Kia Stinger + dat = [ord(i) for i in dat] + checksum = (sum(dat[:6]) + dat[7]) % 256 + + values["CF_Lkas_Chksum"] = checksum + + return packer.make_can_msg("LKAS11", 0, values) + +def create_lkas12(): + return make_can_msg(1342, "\x00\x00\x00\x00\x60\x05", 0) + + +def create_1191(): + return make_can_msg(1191, "\x01\x00", 0) + + +def create_1156(): + return make_can_msg(1156, "\x08\x20\xfe\x3f\x00\xe0\xfd\x3f", 0) + +def create_clu11(packer, clu11, button): + values = { + "CF_Clu_CruiseSwState": button, + "CF_Clu_CruiseSwMain": clu11["CF_Clu_CruiseSwMain"], + "CF_Clu_SldMainSW": clu11["CF_Clu_SldMainSW"], + "CF_Clu_ParityBit1": clu11["CF_Clu_ParityBit1"], + "CF_Clu_VanzDecimal": clu11["CF_Clu_VanzDecimal"], + "CF_Clu_Vanz": clu11["CF_Clu_Vanz"], + "CF_Clu_SPEED_UNIT": clu11["CF_Clu_SPEED_UNIT"], + "CF_Clu_DetentOut": clu11["CF_Clu_DetentOut"], + "CF_Clu_RheostatLevel": clu11["CF_Clu_RheostatLevel"], + "CF_Clu_CluInfo": clu11["CF_Clu_CluInfo"], + "CF_Clu_AmpInfo": clu11["CF_Clu_AmpInfo"], + "CF_Clu_AliveCnt1": 0, + } + + return packer.make_can_msg("CLU11", 0, values) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py new file mode 100644 index 00000000000000..96174ef09643e8 --- /dev/null +++ b/selfdrive/car/hyundai/interface.py @@ -0,0 +1,309 @@ +#!/usr/bin/env python +from cereal import car, log +from common.realtime import sec_since_boot +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.hyundai.carstate import CarState, get_can_parser, get_camera_parser +from selfdrive.car.hyundai.values import CAMERA_MSGS, CAR, get_hud_alerts + +try: + from selfdrive.car.hyundai.carcontroller import CarController +except ImportError: + CarController = None + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + self.VM = VehicleModel(CP) + self.idx = 0 + self.lanes = 0 + self.lkas_request = 0 + + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.can_invalid_count = 0 + self.cruise_enabled_prev = False + self.low_speed_alert = False + + # *** init the major players *** + self.CS = CarState(CP) + self.cp = get_can_parser(CP) + self.cp_cam = get_camera_parser(CP) + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(self.cp.dbc_name, CP.carFingerprint, CP.enableCamera) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 3.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 + + ret = car.CarParams.new_message() + + ret.carName = "hyundai" + ret.carFingerprint = candidate + ret.radarOffCan = True + ret.safetyModel = car.CarParams.SafetyModels.hyundai + ret.enableCruise = True # stock acc + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923 * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 192150 + tireStiffnessRear_civic = 202500 + + ret.steerActuatorDelay = 0.1 # Default delay + tire_stiffness_factor = 1. + + if candidate == CAR.SANTA_FE: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 3982 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.766 + + # Values from optimizer + ret.steerRatio = 16.55 # 13.8 is spec end-to-end + tire_stiffness_factor = 0.82 + + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.37], [0.1]] + ret.minSteerSpeed = 0. + elif candidate == CAR.KIA_SORENTO: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 1985 + std_cargo + ret.wheelbase = 2.78 + ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] + ret.minSteerSpeed = 0. + elif candidate == CAR.ELANTRA: + ret.steerKf = 0.00006 + ret.steerRateCost = 0.5 + ret.mass = 1275 + std_cargo + ret.wheelbase = 2.7 + ret.steerRatio = 13.73 #Spec + tire_stiffness_factor = 0.385 + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] + ret.minSteerSpeed = 32 * CV.MPH_TO_MS + elif candidate == CAR.GENESIS: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 2060 + std_cargo + ret.wheelbase = 3.01 + ret.steerRatio = 16.5 + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.16], [0.01]] + ret.minSteerSpeed = 35 * CV.MPH_TO_MS + elif candidate == CAR.KIA_STINGER: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 1825 + std_cargo + ret.wheelbase = 2.78 + ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] + ret.minSteerSpeed = 0. + + ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this + ret.longitudinalKpBP = [0.] + ret.longitudinalKpV = [0.] + ret.longitudinalKiBP = [0.] + ret.longitudinalKiV = [0.] + + ret.centerToFront = ret.wheelbase * 0.4 + + centerToRear = ret.wheelbase - ret.centerToFront + + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = (tireStiffnessFront_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = (tireStiffnessRear_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + + # no rear steering, at least on the listed cars above + ret.steerRatioRear = 0. + ret.steerControlType = car.CarParams.SteerControlType.torque + + # steer, gas, brake limitations VS speed + ret.steerMaxBP = [0.] + ret.steerMaxV = [1.0] + ret.gasMaxBP = [0.] + ret.gasMaxV = [1.] + ret.brakeMaxBP = [0.] + ret.brakeMaxV = [1.] + ret.longPidDeadzoneBP = [0.] + ret.longPidDeadzoneV = [0.] + + ret.enableCamera = not any(x for x in CAMERA_MSGS if x in fingerprint) + + ret.steerLimitAlert = False + ret.stoppingControl = False + ret.startAccel = 0.0 + + return ret + + # returns a car.CarState + def update(self, c): + # ******************* do can recv ******************* + canMonoTimes = [] + self.cp.update(int(sec_since_boot() * 1e9), False) + self.cp_cam.update(int(sec_since_boot() * 1e9), False) + self.CS.update(self.cp, self.cp_cam) + # create message + ret = car.CarState.new_message() + # speeds + ret.vEgo = self.CS.v_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.aEgo = self.CS.a_ego + ret.yawRate = self.CS.yaw_rate + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # gear shifter + if self.CP.carFingerprint == CAR.ELANTRA: + ret.gearShifter = self.CS.gear_shifter_cluster + else: + ret.gearShifter = self.CS.gear_shifter + + # gas pedal + ret.gas = self.CS.car_gas + ret.gasPressed = self.CS.pedal_gas > 1e-3 # tolerance to avoid false press reading + + # brake pedal + ret.brake = self.CS.user_brake + ret.brakePressed = self.CS.brake_pressed != 0 + ret.brakeLights = self.CS.brake_lights + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + ret.steeringRate = self.CS.angle_steers_rate # it's unsigned + + ret.steeringTorque = self.CS.steer_torque_driver + ret.steeringPressed = self.CS.steer_override + + # cruise state + ret.cruiseState.enabled = self.CS.pcm_acc_status != 0 + if self.CS.pcm_acc_status != 0: + ret.cruiseState.speed = self.CS.cruise_set_speed + else: + ret.cruiseState.speed = 0 + ret.cruiseState.available = bool(self.CS.main_on) + ret.cruiseState.standstill = False + + # TODO: button presses + buttonEvents = [] + + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'leftBlinker' + be.pressed = self.CS.left_blinker_on != 0 + buttonEvents.append(be) + + if self.CS.right_blinker_on != self.CS.prev_right_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'rightBlinker' + be.pressed = self.CS.right_blinker_on != 0 + buttonEvents.append(be) + + ret.buttonEvents = buttonEvents + ret.leftBlinker = bool(self.CS.left_blinker_on) + ret.rightBlinker = bool(self.CS.right_blinker_on) + + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + + + # 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.: + self.low_speed_alert = True + if ret.vEgo > (self.CP.minSteerSpeed + 4.): + self.low_speed_alert = False + + # events + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + if not ret.gearShifter == 'drive': + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.seatbeltUnlatched: + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.esp_disabled: + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if not self.CS.main_on: + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gearShifter == 'reverse': + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.CS.steer_error: + events.append(create_event('steerTempUnavailable', [ET.NO_ENTRY, ET.WARNING])) + + # enable request in prius is simple, as we activate when Toyota is active (rising edge) + if ret.cruiseState.enabled and not self.cruise_enabled_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + elif not ret.cruiseState.enabled: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed and (not self.brake_pressed_prev or ret.vEgoRaw > 0.1)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + + if self.low_speed_alert: + events.append(create_event('belowSteerSpeed', [ET.WARNING])) + + ret.events = events + ret.canMonoTimes = canMonoTimes + + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + self.cruise_enabled_prev = ret.cruiseState.enabled + + return ret.as_reader() + + def apply(self, c, perception_state=log.Live20Data.new_message()): + + hud_alert = get_hud_alerts(c.hudControl.visualAlert, c.hudControl.audibleAlert) + + self.CC.update(self.sendcan, c.enabled, self.CS, c.actuators, + c.cruiseControl.cancel, hud_alert) + + return False diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py new file mode 100644 index 00000000000000..96159fd87d9535 --- /dev/null +++ b/selfdrive/car/hyundai/radar_interface.py @@ -0,0 +1,24 @@ +#!/usr/bin/env python +from cereal import car +import time + + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + self.delay = 0.1 + + def update(self): + + ret = car.RadarState.new_message() + time.sleep(0.05) # radard runs on RI updates + + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print ret diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py new file mode 100644 index 00000000000000..ad5191195b92b1 --- /dev/null +++ b/selfdrive/car/hyundai/values.py @@ -0,0 +1,58 @@ +from cereal import car +from selfdrive.car import dbc_dict + +VisualAlert = car.CarControl.HUDControl.VisualAlert +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + +def get_hud_alerts(visual_alert, audible_alert): + if visual_alert == VisualAlert.steerRequired: + return 4 if audible_alert != AudibleAlert.none else 5 + else: + return 0 + +class CAR: + SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019" + ELANTRA = "HYUNDAI ELANTRA LIMITED ULTIMATE 2017" + GENESIS = "HYUNDAI GENESIS 2018" + KIA_SORENTO = "KIA SORENTO GT LINE 2018" # Top Trim Kia Sorento for Australian Market, AWD Diesel 8sp Auto + KIA_STINGER = "KIA STINGER GT2 2018" + +class Buttons: + NONE = 0 + RES_ACCEL = 1 + SET_DECEL = 2 + CANCEL = 4 + +FINGERPRINTS = { + CAR.SANTA_FE: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8 + }], + CAR.ELANTRA: [{ + 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1345: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2001: 8, 2003: 8, 2004: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], + CAR.GENESIS: [{ + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1342: 6, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 + }], + CAR.KIA_SORENTO: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1 + }], + CAR.KIA_STINGER: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 + }], +} + +CAMERA_MSGS = [832, 1156, 1191, 1342] # msgs sent by the camera + +CHECKSUM = { + "crc8": [CAR.SANTA_FE], + "6B": [CAR.KIA_SORENTO, CAR.GENESIS], + "7B": [CAR.KIA_STINGER, CAR.ELANTRA], +} + +DBC = { + CAR.SANTA_FE: dbc_dict('hyundai_santa_fe_2019_ccan', None), + CAR.ELANTRA: dbc_dict('hyundai_santa_fe_2019_ccan', None), + CAR.GENESIS: dbc_dict('hyundai_santa_fe_2019_ccan', None), + CAR.KIA_SORENTO: dbc_dict('hyundai_santa_fe_2019_ccan', None), + CAR.KIA_STINGER: dbc_dict('hyundai_santa_fe_2019_ccan', None), +} diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 6acad5e5a99a2e..5edbcbbd113f78 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -1,14 +1,10 @@ #!/usr/bin/env python -import os -import time import zmq -from common.realtime import sec_since_boot -import common.numpy_fast as np -from cereal import car +from cereal import car, log from selfdrive.config import Conversions as CV from selfdrive.services import service_list +from selfdrive.swaglog import cloudlog import selfdrive.messaging as messaging -from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event # mocked car interface to work with chffrplus TS = 0.01 # 100Hz @@ -22,7 +18,7 @@ def __init__(self, CP, sendcan=None): self.CP = CP - print "Using Mock Car Interface" + cloudlog.debug("Using Mock Car Interface") context = zmq.Context() # TODO: subscribe to phone sensor @@ -30,6 +26,7 @@ def __init__(self, CP, sendcan=None): self.gps = messaging.sub_sock(context, service_list['gpsLocation'].port) self.speed = 0. + self.prev_speed = 0. self.yaw_rate = 0. self.yaw_rate_meas = 0. @@ -47,7 +44,6 @@ def get_params(candidate, fingerprint): ret = car.CarParams.new_message() ret.carName = "mock" - ret.radarName = "mock" ret.carFingerprint = candidate ret.safetyModel = car.CarParams.SafetyModels.noOutput @@ -76,6 +72,7 @@ def get_params(candidate, fingerprint): ret.longitudinalKpV = [0.] ret.longitudinalKiBP = [0.] ret.longitudinalKiV = [0.] + ret.steerActuatorDelay = 0. return ret @@ -91,6 +88,7 @@ def update(self, c): gps = messaging.recv_sock(self.gps) if gps is not None: + self.prev_speed = self.speed self.speed = gps.gpsLocation.speed # create message @@ -99,7 +97,11 @@ def update(self, c): # speeds ret.vEgo = self.speed ret.vEgoRaw = self.speed - ret.aEgo = 0. + a = self.speed - self.prev_speed + + ret.aEgo = a + ret.brakePressed = a < -0.5 + self.yawRate = LPG * self.yaw_rate_meas + (1. - LPG) * self.yaw_rate ret.yawRate = self.yaw_rate ret.standstill = self.speed < 0.01 @@ -111,11 +113,10 @@ def update(self, c): ret.steeringAngle = curvature * self.CP.steerRatio * self.CP.wheelbase * CV.RAD_TO_DEG events = [] - #events.append(create_event('passive', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) ret.events = events return ret.as_reader() - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): # in mock no carcontrols return False diff --git a/selfdrive/radar/mock/interface.py b/selfdrive/car/mock/radar_interface.py similarity index 87% rename from selfdrive/radar/mock/interface.py rename to selfdrive/car/mock/radar_interface.py index 7a5c66722ad036..ec042d1794a7ec 100755 --- a/selfdrive/radar/mock/interface.py +++ b/selfdrive/car/mock/radar_interface.py @@ -4,7 +4,7 @@ class RadarInterface(object): - def __init__(self): + def __init__(self, CP): # radar self.pts = {} self.delay = 0.1 @@ -17,7 +17,7 @@ def update(self): return ret if __name__ == "__main__": - RI = RadarInterface() + RI = RadarInterface(None) while 1: ret = RI.update() print(chr(27) + "[2J") diff --git a/selfdrive/car/mock/values.py b/selfdrive/car/mock/values.py new file mode 100644 index 00000000000000..0dd91565bde856 --- /dev/null +++ b/selfdrive/car/mock/values.py @@ -0,0 +1,2 @@ +class CAR: + MOCK = 'mock' diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 5b56e2a6f29582..b0c6bf5209f63b 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -1,32 +1,41 @@ +from cereal import car from common.numpy_fast import clip, interp -from common.realtime import sec_since_boot from selfdrive.boardd.boardd import can_list_to_can_capnp -from selfdrive.controls.lib.drive_helpers import rate_limit from selfdrive.car.toyota.toyotacan import make_can_msg, create_video_target,\ create_steer_command, create_ui_command, \ create_ipas_steer_command, create_accel_command, \ create_fcw_command -from selfdrive.car.toyota.values import CAR, ECU, STATIC_MSGS +from selfdrive.car.toyota.values import ECU, STATIC_MSGS +from selfdrive.can.packer import CANPacker +VisualAlert = car.CarControl.HUDControl.VisualAlert +AudibleAlert = car.CarControl.HUDControl.AudibleAlert +# Accel limits ACCEL_HYST_GAP = 0.02 # don't change accel command for small oscilalitons within this value -ACCEL_MAX = 1500 # 1.5 m/s2 -ACCEL_MIN = -3000 # 3 m/s2 +ACCEL_MAX = 1.5 # 1.5 m/s2 +ACCEL_MIN = -3.0 # 3 m/s2 ACCEL_SCALE = max(ACCEL_MAX, -ACCEL_MIN) +# Steer torque limits STEER_MAX = 1500 -STEER_DELTA_UP = 10 # 1.5s time to peak torque -STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) -STEER_ERROR_MAX = 500 # max delta between torque cmd and torque motor +STEER_DELTA_UP = 10 # 1.5s time to peak torque +STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) +STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor -STEER_IPAS_MAX = 340 -STEER_IPAS_DELTA_MAX = 3 +# Steer angle limits (tested at the Crows Landing track and considered ok) +ANGLE_MAX_BP = [0., 5.] +ANGLE_MAX_V = [510., 300.] +ANGLE_DELTA_BP = [0., 5., 15.] +ANGLE_DELTA_V = [5., .8, .15] # windup limit +ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit TARGET_IDS = [0x340, 0x341, 0x342, 0x343, 0x344, 0x345, 0x363, 0x364, 0x365, 0x370, 0x371, 0x372, 0x373, 0x374, 0x375, 0x380, 0x381, 0x382, 0x383] + def accel_hysteresis(accel, accel_steady, enabled): # for small accel oscillations within ACCEL_HYST_GAP, don't change the accel command @@ -49,49 +58,80 @@ def process_hud_alert(hud_alert, audible_alert): sound1 = 0 sound2 = 0 - if hud_alert == 'fcw': + if hud_alert == VisualAlert.fcw: fcw = 1 - elif hud_alert == 'steerRequired': + elif hud_alert == VisualAlert.steerRequired: steer = 1 - if audible_alert == 'chimeRepeated': + if audible_alert == AudibleAlert.chimeWarningRepeat: sound1 = 1 - elif audible_alert in ['beepSingle', 'chimeSingle', 'chimeDouble']: + elif audible_alert != AudibleAlert.none: # TODO: find a way to send single chimes sound2 = 1 return steer, fcw, sound1, sound2 +def ipas_state_transition(steer_angle_enabled, enabled, ipas_active, ipas_reset_counter): + + if enabled and not steer_angle_enabled: + #ipas_reset_counter = max(0, ipas_reset_counter - 1) + #if ipas_reset_counter == 0: + # steer_angle_enabled = True + #else: + # steer_angle_enabled = False + #return steer_angle_enabled, ipas_reset_counter + return True, 0 + + elif enabled and steer_angle_enabled: + if steer_angle_enabled and not ipas_active: + ipas_reset_counter += 1 + else: + ipas_reset_counter = 0 + if ipas_reset_counter > 10: # try every 0.1s + steer_angle_enabled = False + return steer_angle_enabled, ipas_reset_counter + + else: + return False, 0 + + class CarController(object): - def __init__(self, car_fingerprint, enable_camera, enable_dsu, enable_apg): + def __init__(self, dbc_name, car_fingerprint, enable_camera, enable_dsu, enable_apg): self.braking = False # redundant safety check with the board self.controls_allowed = True - self.last_steer = 0. + self.last_steer = 0 + self.last_angle = 0 self.accel_steady = 0. self.car_fingerprint = car_fingerprint self.alert_active = False self.last_standstill = False self.standstill_req = False + self.angle_control = False + + self.steer_angle_enabled = False + self.ipas_reset_counter = 0 + self.last_fault_frame = -200 self.fake_ecus = set() if enable_camera: self.fake_ecus.add(ECU.CAM) if enable_dsu: self.fake_ecus.add(ECU.DSU) if enable_apg: self.fake_ecus.add(ECU.APGS) + self.packer = CANPacker(dbc_name) + def update(self, sendcan, enabled, CS, frame, actuators, - pcm_cancel_cmd, hud_alert, audible_alert): + pcm_cancel_cmd, hud_alert, audible_alert, forwarding_camera): # *** compute control surfaces *** - ts = sec_since_boot() - # steer torque is converted back to CAN reference (positive when steering right) + # gas and brake apply_accel = actuators.gas - actuators.brake apply_accel, self.accel_steady = accel_hysteresis(apply_accel, self.accel_steady, enabled) - apply_accel = int(round(clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, ACCEL_MAX))) + apply_accel = clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, ACCEL_MAX) - # steer torque is converted back to CAN reference (positive when steering right) + # steer torque apply_steer = int(round(actuators.steer * STEER_MAX)) max_lim = min(max(CS.steer_torque_motor + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX) @@ -105,14 +145,42 @@ def update(self, sendcan, enabled, CS, frame, actuators, else: apply_steer = clip(apply_steer, self.last_steer - STEER_DELTA_UP, min(self.last_steer + STEER_DELTA_DOWN, STEER_DELTA_UP)) - if not enabled and CS.pcm_acc_status: - # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated - pcm_cancel_cmd = 1 - # dropping torque immediately might cause eps to temp fault. On the other hand, safety_toyota # cuts steer torque immediately anyway TODO: monitor if this is a real issue - if not enabled or CS.steer_error: + # only cut torque when steer state is a known fault + if CS.steer_state in [9, 25]: + self.last_fault_frame = frame + + # Cut steering for 2s after fault + if not enabled or (frame - self.last_fault_frame < 200): apply_steer = 0 + apply_steer_req = 0 + else: + apply_steer_req = 1 + + self.steer_angle_enabled, self.ipas_reset_counter = \ + ipas_state_transition(self.steer_angle_enabled, enabled, CS.ipas_active, self.ipas_reset_counter) + #print self.steer_angle_enabled, self.ipas_reset_counter, CS.ipas_active + + # steer angle + if self.steer_angle_enabled and CS.ipas_active: + apply_angle = actuators.steerAngle + angle_lim = interp(CS.v_ego, ANGLE_MAX_BP, ANGLE_MAX_V) + apply_angle = clip(apply_angle, -angle_lim, angle_lim) + + # windup slower + if self.last_angle * apply_angle > 0. and abs(apply_angle) > abs(self.last_angle): + angle_rate_lim = interp(CS.v_ego, ANGLE_DELTA_BP, ANGLE_DELTA_V) + else: + angle_rate_lim = interp(CS.v_ego, ANGLE_DELTA_BP, ANGLE_DELTA_VU) + + apply_angle = clip(apply_angle, self.last_angle - angle_rate_lim, self.last_angle + angle_rate_lim) + else: + apply_angle = CS.angle_steers + + if not enabled and CS.pcm_acc_status: + # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated + pcm_cancel_cmd = 1 # on entering standstill, send standstill request if CS.standstill and not self.last_standstill: @@ -122,6 +190,7 @@ def update(self, sendcan, enabled, CS, frame, actuators, self.standstill_req = False self.last_steer = apply_steer + self.last_angle = apply_angle self.last_accel = apply_accel self.last_standstill = CS.standstill @@ -134,19 +203,25 @@ def update(self, sendcan, enabled, CS, frame, actuators, # sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed # on consecutive messages if ECU.CAM in self.fake_ecus: - can_sends.append(create_steer_command(apply_steer, frame)) + if self.angle_control: + can_sends.append(create_steer_command(self.packer, 0., 0, frame)) + else: + can_sends.append(create_steer_command(self.packer, apply_steer, apply_steer_req, frame)) - if ECU.APGS in self.fake_ecus: - can_sends.append(create_ipas_steer_command(apply_steer)) + if self.angle_control: + can_sends.append(create_ipas_steer_command(self.packer, apply_angle, self.steer_angle_enabled, + ECU.APGS in self.fake_ecus)) + elif ECU.APGS in self.fake_ecus: + can_sends.append(create_ipas_steer_command(self.packer, 0, 0, True)) # accel cmd comes from DSU, but we can spam can to cancel the system even if we are using lat only control if (frame % 3 == 0 and ECU.DSU in self.fake_ecus) or (pcm_cancel_cmd and ECU.CAM in self.fake_ecus): if ECU.DSU in self.fake_ecus: - can_sends.append(create_accel_command(apply_accel, pcm_cancel_cmd, self.standstill_req)) + can_sends.append(create_accel_command(self.packer, apply_accel, pcm_cancel_cmd, self.standstill_req)) else: - can_sends.append(create_accel_command(0, pcm_cancel_cmd, False)) + can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False)) - if frame % 10 == 0 and ECU.CAM in self.fake_ecus: + if frame % 10 == 0 and ECU.CAM in self.fake_ecus and not forwarding_camera: for addr in TARGET_IDS: can_sends.append(create_video_target(frame/10, addr)) @@ -164,13 +239,15 @@ def update(self, sendcan, enabled, CS, frame, actuators, send_ui = False if (frame % 100 == 0 or send_ui) and ECU.CAM in self.fake_ecus: - can_sends.append(create_ui_command(steer, sound1, sound2)) - can_sends.append(create_fcw_command(fcw)) + can_sends.append(create_ui_command(self.packer, steer, sound1, sound2)) + + if frame % 100 == 0 and ECU.DSU in self.fake_ecus: + can_sends.append(create_fcw_command(self.packer, fcw)) #*** static msgs *** - for addr, (ecu, cars, bus, fr_step, vl) in STATIC_MSGS.iteritems(): - if frame % fr_step == 0 and ecu in self.fake_ecus and self.car_fingerprint in cars: + for (addr, ecu, cars, bus, fr_step, vl) in STATIC_MSGS: + if frame % fr_step == 0 and ecu in self.fake_ecus and self.car_fingerprint in cars and not (ecu == ECU.CAM and forwarding_camera): # special cases if fr_step == 5 and ecu == ECU.CAM and bus == 1: cnt = (((frame / 5) % 7) + 1) << 5 diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index e85902f944b9e5..71d33b0ab7c2a2 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -1,118 +1,87 @@ -import os -import selfdrive.messaging as messaging -from selfdrive.car.toyota.values import CAR -from selfdrive.can.parser import CANParser -from selfdrive.config import Conversions as CV import numpy as np +from common.kalman.simple_kalman import KF1D +from selfdrive.can.parser import CANParser, CANDefine +from selfdrive.config import Conversions as CV +from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD + +def parse_gear_shifter(gear, vals): -def parse_gear_shifter(can_gear, car_fingerprint): - - if car_fingerprint == CAR.PRIUS: - if can_gear == 0x0: - return "park" - elif can_gear == 0x1: - return "reverse" - elif can_gear == 0x2: - return "neutral" - elif can_gear == 0x3: - return "drive" - elif can_gear == 0x4: - return "brake" - elif car_fingerprint in [CAR.RAV4, CAR.RAV4H]: - if can_gear == 0x20: - return "park" - elif can_gear == 0x10: - return "reverse" - elif can_gear == 0x8: - return "neutral" - elif can_gear == 0x0: - return "drive" - elif can_gear == 0x1: - return "sport" - - return "unknown" + val_to_capnp = {'P': 'park', 'R': 'reverse', 'N': 'neutral', + 'D': 'drive', 'B': 'brake'} + try: + return val_to_capnp[vals[gear]] + except KeyError: + return "unknown" def get_can_parser(CP): - # this function generates lists for signal, messages and initial values - if CP.carFingerprint == CAR.PRIUS: - dbc_f = 'toyota_prius_2017_pt.dbc' - signals = [ - ("GEAR", 295, 0), - ("BRAKE_PRESSED", 550, 0), - ("GAS_PEDAL", 581, 0), - ] - checks = [ - (550, 40), - (581, 33) - ] - elif CP.carFingerprint == CAR.RAV4H: - dbc_f = 'toyota_rav4_hybrid_2017_pt.dbc' - signals = [ - ("GEAR", 956, 0), - ("BRAKE_PRESSED", 550, 0), - ("GAS_PEDAL", 581, 0), - ] - checks = [ - (550, 40), - (581, 33) - ] - elif CP.carFingerprint == CAR.RAV4: - dbc_f = 'toyota_rav4_2017_pt.dbc' - signals = [ - ("GEAR", 956, 0x20), - ("BRAKE_PRESSED", 548, 0), - ("GAS_PEDAL", 705, 0), - ] - checks = [ - (548, 40), - (705, 33) - ] - - # TODO: DOORS, GAS_PEDAL, BRAKE_PRESSED for RAV4 - signals += [ + + signals = [ # sig_name, sig_address, default - ("WHEEL_SPEED_FL", 170, 0), - ("WHEEL_SPEED_FR", 170, 0), - ("WHEEL_SPEED_RL", 170, 0), - ("WHEEL_SPEED_RR", 170, 0), - ("DOOR_OPEN_FL", 1568, 1), - ("DOOR_OPEN_FR", 1568, 1), - ("DOOR_OPEN_RL", 1568, 1), - ("DOOR_OPEN_RR", 1568, 1), - ("SEATBELT_DRIVER_UNLATCHED", 1568, 1), - ("TC_DISABLED", 951, 1), - ("STEER_ANGLE", 37, 0), - ("STEER_FRACTION", 37, 0), - ("STEER_RATE", 37, 0), - ("GAS_RELEASED", 466, 0), - ("CRUISE_STATE", 466, 0), - ("MAIN_ON", 467, 0), - ("SET_SPEED", 467, 0), - ("LOW_SPEED_LOCKOUT", 467, 0), - ("STEER_TORQUE_DRIVER", 608, 0), - ("STEER_TORQUE_EPS", 608, 0), - ("TURN_SIGNALS", 1556, 3), # 3 is no blinkers - ("LKA_STATE", 610, 0), - ("BRAKE_LIGHTS_ACC", 951, 0), + ("GEAR", "GEAR_PACKET", 0), + ("BRAKE_PRESSED", "BRAKE_MODULE", 0), + ("GAS_PEDAL", "GAS_PEDAL", 0), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), + ("DOOR_OPEN_FL", "SEATS_DOORS", 1), + ("DOOR_OPEN_FR", "SEATS_DOORS", 1), + ("DOOR_OPEN_RL", "SEATS_DOORS", 1), + ("DOOR_OPEN_RR", "SEATS_DOORS", 1), + ("SEATBELT_DRIVER_UNLATCHED", "SEATS_DOORS", 1), + ("TC_DISABLED", "ESP_CONTROL", 1), + ("STEER_ANGLE", "STEER_ANGLE_SENSOR", 0), + ("STEER_FRACTION", "STEER_ANGLE_SENSOR", 0), + ("STEER_RATE", "STEER_ANGLE_SENSOR", 0), + ("GAS_RELEASED", "PCM_CRUISE", 0), + ("CRUISE_ACTIVE", "PCM_CRUISE", 0), + ("CRUISE_STATE", "PCM_CRUISE", 0), + ("MAIN_ON", "PCM_CRUISE_2", 0), + ("SET_SPEED", "PCM_CRUISE_2", 0), + ("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2", 0), + ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR", 0), + ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR", 0), + ("TURN_SIGNALS", "STEERING_LEVERS", 3), # 3 is no blinkers + ("LKA_STATE", "EPS_STATUS", 0), + ("IPAS_STATE", "EPS_STATUS", 1), + ("BRAKE_LIGHTS_ACC", "ESP_CONTROL", 0), + ("AUTO_HIGH_BEAM", "LIGHT_STALK", 0), ] - checks += [ - (170, 80), - (37, 80), - (466, 33), - (467, 33), - (608, 50), - (610, 25), + checks = [ + ("BRAKE_MODULE", 40), + ("GAS_PEDAL", 33), + ("WHEEL_SPEEDS", 80), + ("STEER_ANGLE_SENSOR", 80), + ("PCM_CRUISE", 33), + ("PCM_CRUISE_2", 33), + ("STEER_TORQUE_SENSOR", 50), + ("EPS_STATUS", 25), ] - return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 0) + if CP.carFingerprint == CAR.PRIUS: + signals += [("STATE", "AUTOPARK_STATUS", 0)] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + + +def get_cam_can_parser(CP): + + signals = [] + + # use steering message to check if panda is connected to frc + checks = [("STEERING_LKA", 42)] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) class CarState(object): def __init__(self, CP): self.CP = CP + self.can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + self.shifter_values = self.can_define.dv["GEAR_PACKET"]['GEAR'] self.left_blinker_on = 0 self.right_blinker_on = 0 @@ -121,82 +90,75 @@ def __init__(self, CP): # vEgo kalman filter dt = 0.01 - self.v_ego_x = np.matrix([[0.0], [0.0]]) - self.v_ego_A = np.matrix([[1.0, dt], [0.0, 1.0]]) - self.v_ego_C = np.matrix([1.0, 0.0]) - self.v_ego_Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) - self.v_ego_R = 1e3 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) self.v_ego = 0.0 - # import control - # (x, l, K) = control.dare(np.transpose(A), np.transpose(C), Q, R) - # self.v_ego_K = np.transpose(K) - self.v_ego_K = np.matrix([[0.12287673], [0.29666309]]) - - def update(self, cp): + def update(self, cp, cp_cam): # copy can_valid self.can_valid = cp.can_valid - - if self.car_fingerprint == CAR.PRIUS: - can_gear = cp.vl[295]['GEAR'] - self.brake_pressed = cp.vl[550]['BRAKE_PRESSED'] - self.pedal_gas = cp.vl[581]['GAS_PEDAL'] - elif self.car_fingerprint == CAR.RAV4H: - can_gear = cp.vl[956]['GEAR'] - self.brake_pressed = cp.vl[550]['BRAKE_PRESSED'] - self.pedal_gas = cp.vl[581]['GAS_PEDAL'] - elif self.car_fingerprint == CAR.RAV4: - can_gear = cp.vl[956]['GEAR'] - self.brake_pressed = cp.vl[548]['BRAKE_PRESSED'] - self.pedal_gas = cp.vl[705]['GAS_PEDAL'] + self.cam_can_valid = cp_cam.can_valid # update prevs, update must run once per loop self.prev_left_blinker_on = self.left_blinker_on self.prev_right_blinker_on = self.right_blinker_on - # ******************* parse out can ******************* - self.door_all_closed = not any([cp.vl[1568]['DOOR_OPEN_FL'], cp.vl[1568]['DOOR_OPEN_FR'], - cp.vl[1568]['DOOR_OPEN_RL'], cp.vl[1568]['DOOR_OPEN_RR']]) - self.seatbelt = not cp.vl[1568]['SEATBELT_DRIVER_UNLATCHED'] - # whitelist instead of blacklist, safer at the expense of disengages - self.steer_error = False - self.brake_error = 0 - self.esp_disabled = cp.vl[951]['TC_DISABLED'] + self.door_all_closed = not any([cp.vl["SEATS_DOORS"]['DOOR_OPEN_FL'], cp.vl["SEATS_DOORS"]['DOOR_OPEN_FR'], + cp.vl["SEATS_DOORS"]['DOOR_OPEN_RL'], cp.vl["SEATS_DOORS"]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl["SEATS_DOORS"]['SEATBELT_DRIVER_UNLATCHED'] + + self.brake_pressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED'] + self.pedal_gas = cp.vl["GAS_PEDAL"]['GAS_PEDAL'] + self.car_gas = self.pedal_gas + self.esp_disabled = cp.vl["ESP_CONTROL"]['TC_DISABLED'] + # calc best v_ego estimate, by averaging two opposite corners - self.v_wheel_fl = cp.vl[170]['WHEEL_SPEED_FL'] - self.v_wheel_fr = cp.vl[170]['WHEEL_SPEED_FR'] - self.v_wheel_rl = cp.vl[170]['WHEEL_SPEED_RL'] - self.v_wheel_rr = cp.vl[170]['WHEEL_SPEED_RR'] - self.v_wheel = ( - cp.vl[170]['WHEEL_SPEED_FL'] + cp.vl[170]['WHEEL_SPEED_FR'] + - cp.vl[170]['WHEEL_SPEED_RL'] + cp.vl[170]['WHEEL_SPEED_RR']) / 4. * CV.KPH_TO_MS + self.v_wheel_fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS + self.v_wheel_fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS + self.v_wheel_rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS + self.v_wheel_rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS + self.v_wheel = float(np.mean([self.v_wheel_fl, self.v_wheel_fr, self.v_wheel_rl, self.v_wheel_rr])) # Kalman filter if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) - self.v_ego_x = np.dot((self.v_ego_A - np.dot(self.v_ego_K, self.v_ego_C)), self.v_ego_x) + np.dot(self.v_ego_K, self.v_wheel) + self.v_ego_raw = self.v_wheel - self.v_ego = float(self.v_ego_x[0]) - self.a_ego = float(self.v_ego_x[1]) + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) self.standstill = not self.v_wheel > 0.001 - self.angle_steers = cp.vl[37]['STEER_ANGLE'] + cp.vl[37]['STEER_FRACTION'] - self.angle_steers_rate = cp.vl[37]['STEER_RATE'] - self.gear_shifter = parse_gear_shifter(can_gear, self.car_fingerprint) - self.main_on = cp.vl[467]['MAIN_ON'] - self.left_blinker_on = cp.vl[1556]['TURN_SIGNALS'] == 1 - self.right_blinker_on = cp.vl[1556]['TURN_SIGNALS'] == 2 - + self.angle_steers = cp.vl["STEER_ANGLE_SENSOR"]['STEER_ANGLE'] + cp.vl["STEER_ANGLE_SENSOR"]['STEER_FRACTION'] + self.angle_steers_rate = cp.vl["STEER_ANGLE_SENSOR"]['STEER_RATE'] + can_gear = int(cp.vl["GEAR_PACKET"]['GEAR']) + self.gear_shifter = parse_gear_shifter(can_gear, self.shifter_values) + self.main_on = cp.vl["PCM_CRUISE_2"]['MAIN_ON'] + self.left_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 1 + self.right_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 2 + + # 2 is standby, 10 is active. TODO: check that everything else is really a faulty state + self.steer_state = cp.vl["EPS_STATUS"]['LKA_STATE'] + self.steer_error = cp.vl["EPS_STATUS"]['LKA_STATE'] not in [1, 5] + self.ipas_active = cp.vl['EPS_STATUS']['IPAS_STATE'] == 3 + self.brake_error = 0 + self.steer_torque_driver = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER'] + self.steer_torque_motor = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_EPS'] # we could use the override bit from dbc, but it's triggered at too high torque values - self.steer_override = abs(cp.vl[608]['STEER_TORQUE_DRIVER']) > 100 - self.steer_error = cp.vl[610]['LKA_STATE'] == 50 - self.steer_torque_driver = cp.vl[608]['STEER_TORQUE_DRIVER'] - self.steer_torque_motor = cp.vl[608]['STEER_TORQUE_EPS'] + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD self.user_brake = 0 - self.v_cruise_pcm = cp.vl[467]['SET_SPEED'] - self.pcm_acc_status = cp.vl[466]['CRUISE_STATE'] - self.car_gas = self.pedal_gas - self.gas_pressed = not cp.vl[466]['GAS_RELEASED'] - self.low_speed_lockout = cp.vl[467]['LOW_SPEED_LOCKOUT'] == 2 - self.brake_lights = bool(cp.vl[951]['BRAKE_LIGHTS_ACC'] or self.brake_pressed) + self.v_cruise_pcm = cp.vl["PCM_CRUISE_2"]['SET_SPEED'] + self.pcm_acc_status = cp.vl["PCM_CRUISE"]['CRUISE_STATE'] + self.pcm_acc_active = bool(cp.vl["PCM_CRUISE"]['CRUISE_ACTIVE']) + self.gas_pressed = not cp.vl["PCM_CRUISE"]['GAS_RELEASED'] + self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]['LOW_SPEED_LOCKOUT'] == 2 + self.brake_lights = bool(cp.vl["ESP_CONTROL"]['BRAKE_LIGHTS_ACC'] or self.brake_pressed) + if self.CP.carFingerprint == CAR.PRIUS: + self.generic_toggle = cp.vl["AUTOPARK_STATUS"]['STATE'] != 0 + else: + self.generic_toggle = bool(cp.vl["LIGHT_STALK"]['AUTO_HIGH_BEAM']) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index c490c1db23d4d0..57e90339cc6ae7 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -1,40 +1,43 @@ #!/usr/bin/env python -import os from common.realtime import sec_since_boot -import common.numpy_fast as np -from cereal import car +from cereal import car, log from selfdrive.config import Conversions as CV -from selfdrive.services import service_list -import selfdrive.messaging as messaging from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event from selfdrive.controls.lib.vehicle_model import VehicleModel -from selfdrive.car.toyota.carstate import CarState, get_can_parser -from selfdrive.car.toyota.values import CAR, ECU, check_ecu_msgs +from selfdrive.car.toyota.carstate import CarState, get_can_parser, get_cam_can_parser +from selfdrive.car.toyota.values import ECU, check_ecu_msgs, CAR +from selfdrive.swaglog import cloudlog + try: from selfdrive.car.toyota.carcontroller import CarController except ImportError: CarController = None + class CarInterface(object): def __init__(self, CP, sendcan=None): self.CP = CP self.VM = VehicleModel(CP) self.frame = 0 - self.can_invalid_count = 0 self.gas_pressed_prev = False self.brake_pressed_prev = False + self.can_invalid_count = 0 + self.cam_can_valid_count = 0 self.cruise_enabled_prev = False # *** init the major players *** self.CS = CarState(CP) self.cp = get_can_parser(CP) + self.cp_cam = get_cam_can_parser(CP) + + self.forwarding_camera = False # sending if read only is False if sendcan is not None: self.sendcan = sendcan - self.CC = CarController(CP.carFingerprint, CP.enableCamera, CP.enableDsu, CP.enableApgs) + self.CC = CarController(self.cp.dbc_name, CP.carFingerprint, CP.enableCamera, CP.enableDsu, CP.enableApgs) @staticmethod def compute_gb(accel, speed): @@ -53,42 +56,104 @@ def get_params(candidate, fingerprint): ret = car.CarParams.new_message() ret.carName = "toyota" - ret.radarName = "toyota" ret.carFingerprint = candidate ret.safetyModel = car.CarParams.SafetyModels.toyota - ret.enableSteer = True - ret.enableBrake = True - # pedal ret.enableCruise = True # FIXME: hardcoding honda civic 2016 touring params so they can be used to # scale unknown params for other cars - mass_civic = 2923./2.205 + std_cargo + mass_civic = 2923 * CV.LB_TO_KG + std_cargo wheelbase_civic = 2.70 centerToFront_civic = wheelbase_civic * 0.4 centerToRear_civic = wheelbase_civic - centerToFront_civic rotationalInertia_civic = 2500 - tireStiffnessFront_civic = 85400 - tireStiffnessRear_civic = 90000 + tireStiffnessFront_civic = 192150 + tireStiffnessRear_civic = 202500 + + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay - ret.mass = 3045./2.205 + std_cargo - ret.wheelbase = 2.70 if candidate == CAR.PRIUS else 2.65 + if candidate == CAR.PRIUS: + ret.safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.70 + ret.steerRatio = 15.00 # unknown end-to-end spec + tire_stiffness_factor = 0.6371 # hand-tune + ret.mass = 3045 * CV.LB_TO_KG + std_cargo + ret.steerKpV, ret.steerKiV = [[0.4], [0.01]] + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + # TODO: Prius seem to have very laggy actuators. Understand if it is lag or hysteresis + ret.steerActuatorDelay = 0.25 + + elif candidate in [CAR.RAV4, CAR.RAV4H]: + ret.safetyParam = 73 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.65 + ret.steerRatio = 16.30 # 14.5 is spec end-to-end + tire_stiffness_factor = 0.5533 + ret.mass = 3650 * CV.LB_TO_KG + std_cargo # mean between normal and hybrid + ret.steerKpV, ret.steerKiV = [[0.6], [0.05]] + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + + elif candidate == CAR.COROLLA: + ret.safetyParam = 100 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.70 + ret.steerRatio = 17.8 + tire_stiffness_factor = 0.444 + ret.mass = 2860 * CV.LB_TO_KG + std_cargo # mean between normal and hybrid + ret.steerKpV, ret.steerKiV = [[0.2], [0.05]] + ret.steerKf = 0.00003 # full torque for 20 deg at 80mph means 0.00007818594 + + elif candidate == CAR.LEXUS_RXH: + ret.safetyParam = 100 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.79 + ret.steerRatio = 16. # 14.8 is spec end-to-end + tire_stiffness_factor = 0.444 # not optimized yet + ret.mass = 4481 * CV.LB_TO_KG + std_cargo # mean between min and max + ret.steerKpV, ret.steerKiV = [[0.6], [0.1]] + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + + elif candidate in [CAR.CHR, CAR.CHRH]: + ret.safetyParam = 100 + ret.wheelbase = 2.63906 + ret.steerRatio = 13.6 + tire_stiffness_factor = 0.7933 + ret.mass = 3300. * CV.LB_TO_KG + std_cargo + ret.steerKpV, ret.steerKiV = [[0.723], [0.0428]] + ret.steerKf = 0.00006 + + elif candidate in [CAR.CAMRY, CAR.CAMRYH]: + ret.safetyParam = 100 + ret.wheelbase = 2.82448 + ret.steerRatio = 13.7 + tire_stiffness_factor = 0.7933 + ret.mass = 3400 * CV.LB_TO_KG + std_cargo #mean between normal and hybrid + ret.steerKpV, ret.steerKiV = [[0.6], [0.1]] + ret.steerKf = 0.00006 + + elif candidate in [CAR.HIGHLANDER, CAR.HIGHLANDERH]: + ret.safetyParam = 100 + ret.wheelbase = 2.78 + ret.steerRatio = 16.0 + tire_stiffness_factor = 0.444 # not optimized yet + ret.mass = 4607 * CV.LB_TO_KG + std_cargo #mean between normal and hybrid limited + ret.steerKpV, ret.steerKiV = [[0.6], [0.05]] + ret.steerKf = 0.00006 + + ret.steerRateCost = 1. ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 14.5 #Rav4 2017, TODO: find exact value for Prius - ret.steerKp, ret.steerKi = 0.6, 0.05 - ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 ret.longPidDeadzoneBP = [0., 9.] ret.longPidDeadzoneV = [0., .15] # 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. - if candidate in [CAR.PRIUS, CAR.RAV4H]: # rav4 hybrid can do stop and go + # hybrid models can't do stop and go even though the stock ACC can't + if candidate in [CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.CHR, + CAR.CHRH, CAR.CAMRY, CAR.CAMRYH, CAR.HIGHLANDERH, CAR.HIGHLANDER]: ret.minEnableSpeed = -1. - elif candidate == CAR.RAV4: # TODO: hack ICE Rav4 to do stop and go + elif candidate in [CAR.RAV4, CAR.COROLLA]: # TODO: hack ICE to do stop and go ret.minEnableSpeed = 19. * CV.MPH_TO_MS centerToRear = ret.wheelbase - ret.centerToFront @@ -99,15 +164,16 @@ def get_params(candidate, fingerprint): # TODO: start from empirically derived lateral slip stiffness for the civic and scale by # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront = tireStiffnessFront_civic * \ + ret.tireStiffnessFront = (tireStiffnessFront_civic * tire_stiffness_factor) * \ ret.mass / mass_civic * \ (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) - ret.tireStiffnessRear = tireStiffnessRear_civic * \ + ret.tireStiffnessRear = (tireStiffnessRear_civic * tire_stiffness_factor) * \ ret.mass / mass_civic * \ (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) # no rear steering, at least on the listed cars above ret.steerRatioRear = 0. + ret.steerControlType = car.CarParams.SteerControlType.torque # steer, gas, brake limitations VS speed ret.steerMaxBP = [16. * CV.KPH_TO_MS, 45. * CV.KPH_TO_MS] # breakpoints at 1 and 40 kph @@ -117,13 +183,12 @@ def get_params(candidate, fingerprint): ret.brakeMaxBP = [5., 20.] ret.brakeMaxV = [1., 0.8] - ret.enableCamera = not check_ecu_msgs(fingerprint, candidate, ECU.CAM) - ret.enableDsu = not check_ecu_msgs(fingerprint, candidate, ECU.DSU) - ret.enableApgs = False # not check_ecu_msgs(fingerprint, candidate, ECU.APGS) - print "ECU Camera Simulated: ", ret.enableCamera - print "ECU DSU Simulated: ", ret.enableDsu - print "ECU APGS Simulated: ", ret.enableApgs - ret.enableGas = True + ret.enableCamera = not check_ecu_msgs(fingerprint, ECU.CAM) + ret.enableDsu = not check_ecu_msgs(fingerprint, ECU.DSU) + ret.enableApgs = False #not check_ecu_msgs(fingerprint, ECU.APGS) + cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera) + cloudlog.warn("ECU DSU Simulated: %r", ret.enableDsu) + cloudlog.warn("ECU APGS Simulated: %r", ret.enableApgs) ret.steerLimitAlert = False ret.stoppingControl = False @@ -134,22 +199,20 @@ def get_params(candidate, fingerprint): ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.54, 0.36] - if candidate == CAR.PRIUS: - ret.steerRateCost = 2. - elif candidate in [CAR.RAV4, CAR.RAV4H]: - ret.steerRateCost = 1. - return ret # returns a car.CarState def update(self, c): # ******************* do can recv ******************* - can_pub_main = [] canMonoTimes = [] self.cp.update(int(sec_since_boot() * 1e9), False) - self.CS.update(self.cp) + # run the cam can update for 10s as we just need to know if the camera is alive + if self.frame < 1000: + self.cp_cam.update(int(sec_since_boot() * 1e9), False) + + self.CS.update(self.cp, self.cp_cam) # create message ret = car.CarState.new_message() @@ -169,7 +232,7 @@ def update(self, c): ret.gearShifter = self.CS.gear_shifter # gas pedal - ret.gas = self.CS.car_gas / 256.0 + ret.gas = self.CS.car_gas ret.gasPressed = self.CS.pedal_gas > 0 # brake pedal @@ -181,24 +244,22 @@ def update(self, c): ret.steeringAngle = self.CS.angle_steers ret.steeringRate = self.CS.angle_steers_rate - ret.steeringTorque = 0 + ret.steeringTorque = self.CS.steer_torque_driver ret.steeringPressed = self.CS.steer_override # cruise state - ret.cruiseState.enabled = self.CS.pcm_acc_status != 0 + ret.cruiseState.enabled = self.CS.pcm_acc_active ret.cruiseState.speed = self.CS.v_cruise_pcm * CV.KPH_TO_MS ret.cruiseState.available = bool(self.CS.main_on) ret.cruiseState.speedOffset = 0. - if self.CP.carFingerprint == CAR.RAV4H: - # ignore standstill in hybrid rav4, since pcm allows to restart without + if self.CP.carFingerprint in [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER]: + # ignore standstill in hybrid vehicles, since pcm allows to restart without # receiving any special command ret.cruiseState.standstill = False else: - ret.cruiseState.standstill = self.CS.pcm_acc_status == 7 + ret.cruiseState.standstill = self.CS.pcm_acc_status == 7 - # TODO: button presses buttonEvents = [] - if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: be = car.CarState.ButtonEvent.new_message() be.type = 'leftBlinker' @@ -215,6 +276,11 @@ def update(self, c): ret.leftBlinker = bool(self.CS.left_blinker_on) ret.rightBlinker = bool(self.CS.right_blinker_on) + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + + ret.genericToggle = self.CS.generic_toggle + # events events = [] if not self.CS.can_valid: @@ -223,11 +289,17 @@ def update(self, c): events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) else: self.can_invalid_count = 0 + + if self.CS.cam_can_valid: + self.cam_can_valid_count += 1 + if self.cam_can_valid_count >= 5: + self.forwarding_camera = True + if not ret.gearShifter == 'drive' and self.CP.enableDsu: events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.door_all_closed: + if ret.doorOpen: events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.seatbelt: + if ret.seatbeltUnlatched: events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if self.CS.esp_disabled and self.CP.enableDsu: events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) @@ -273,11 +345,11 @@ def update(self, c): # pass in a car.CarControl # to be called @ 100hz - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert, - c.hudControl.audibleAlert) + c.hudControl.audibleAlert, self.forwarding_camera) self.frame += 1 return False diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py new file mode 100755 index 00000000000000..9711f1393ff566 --- /dev/null +++ b/selfdrive/car/toyota/radar_interface.py @@ -0,0 +1,107 @@ +#!/usr/bin/env python +import os +import zmq +import time +from selfdrive.can.parser import CANParser +from cereal import car +from common.realtime import sec_since_boot +from selfdrive.services import service_list +import selfdrive.messaging as messaging +from selfdrive.car.toyota.values import NO_DSU_CAR + + +RADAR_A_MSGS = list(range(0x210, 0x220)) +RADAR_B_MSGS = list(range(0x220, 0x230)) + +def _create_radard_can_parser(): + dbc_f = 'toyota_prius_2017_adas.dbc' + + msg_a_n = len(RADAR_A_MSGS) + msg_b_n = len(RADAR_B_MSGS) + + signals = zip(['LONG_DIST'] * msg_a_n + ['NEW_TRACK'] * msg_a_n + ['LAT_DIST'] * msg_a_n + + ['REL_SPEED'] * msg_a_n + ['VALID'] * msg_a_n + ['SCORE'] * msg_b_n, + RADAR_A_MSGS * 5 + RADAR_B_MSGS, + [255] * msg_a_n + [1] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_b_n) + + checks = zip(RADAR_A_MSGS + RADAR_B_MSGS, [20]*(msg_a_n + msg_b_n)) + + return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) + + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + self.valid_cnt = {key: 0 for key in RADAR_A_MSGS} + self.track_id = 0 + + self.delay = 0.0 # Delay of radar + + self.rcp = _create_radard_can_parser() + self.no_dsu_car = CP.carFingerprint in NO_DSU_CAR + + context = zmq.Context() + self.logcan = messaging.sub_sock(context, service_list['can'].port) + + def update(self): + + ret = car.RadarState.new_message() + if self.no_dsu_car: + # TODO: make a adas dbc file for dsu-less models + time.sleep(0.05) + return ret + + canMonoTimes = [] + updated_messages = set() + while 1: + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + if RADAR_B_MSGS[-1] in updated_messages: + break + + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + ret.errors = errors + ret.canMonoTimes = canMonoTimes + + for ii in updated_messages: + if ii in RADAR_A_MSGS: + cpt = self.rcp.vl[ii] + + if cpt['LONG_DIST'] >=255 or cpt['NEW_TRACK']: + self.valid_cnt[ii] = 0 # reset counter + if cpt['VALID'] and cpt['LONG_DIST'] < 255: + self.valid_cnt[ii] += 1 + else: + self.valid_cnt[ii] = max(self.valid_cnt[ii] -1, 0) + + score = self.rcp.vl[ii+16]['SCORE'] + # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] + + # radar point only valid if it's a valid measurement and score is above 50 + if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = car.RadarState.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = bool(cpt['VALID']) + else: + if ii in self.pts: + del self.pts[ii] + + ret.points = self.pts.values() + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print(ret) diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py index 812032f8dca574..6587f32f66c06a 100644 --- a/selfdrive/car/toyota/toyotacan.py +++ b/selfdrive/car/toyota/toyotacan.py @@ -1,6 +1,4 @@ import struct -import common.numpy_fast as np -from selfdrive.config import Conversions as CV # *** Toyota specific *** @@ -9,83 +7,97 @@ def fix(msg, addr): checksum = 0 idh = (addr & 0xff00) >> 8 idl = (addr & 0xff) - + checksum = idh + idl + len(msg) + 1 for d_byte in msg: checksum += ord(d_byte) - + #return msg + chr(checksum & 0xFF) return msg + struct.pack("B", checksum & 0xFF) - - + + def make_can_msg(addr, dat, alt, cks=False): if cks: dat = fix(dat, addr) return [addr, 0, dat, alt] - - + + def create_video_target(frame, addr): counter = frame & 0xff msg = struct.pack("!BBBBBBB", counter, 0x03, 0xff, 0x00, 0x00, 0x00, 0x00) return make_can_msg(addr, msg, 1, True) -def create_ipas_steer_command(steer): - +def create_ipas_steer_command(packer, steer, enabled, apgs_enabled): """Creates a CAN message for the Toyota Steer Command.""" if steer < 0: - move = 0x60 - steer = 0xfff + steer + 1 + direction = 3 elif steer > 0: - move = 0x20 + direction = 1 else: - move = 0x40 - - mode = 0x30 if steer else 0x10 - - steer_h = (steer & 0xF00) >> 8 - steer_l = steer & 0xff - - msg = struct.pack("!BBBBBBB", mode | steer_h, steer_l, 0x10, 0x00, move, 0x40, 0x00) + direction = 2 + + mode = 3 if enabled else 1 + + values = { + "STATE": mode, + "DIRECTION_CMD": direction, + "ANGLE": steer, + "SET_ME_X10": 0x10, + "SET_ME_X40": 0x40 + } + if apgs_enabled: + return packer.make_can_msg("STEERING_IPAS", 0, values) + else: + return packer.make_can_msg("STEERING_IPAS_COMMA", 0, values) - return make_can_msg(0x266, msg, 0, True) -def create_steer_command(steer, raw_cnt): +def create_steer_command(packer, steer, steer_req, raw_cnt): """Creates a CAN message for the Toyota Steer Command.""" - # from 0x80 to 0xff - counter = ((raw_cnt & 0x3f) << 1) | 0x80 - if steer != 0: - counter |= 1 - - # hud - # 00 => Regular - # 40 => Actively Steering (with beep) - # 80 => Actively Steering (without beep) - hud = 0x00 - - msg = struct.pack("!BhB", counter, steer, hud) - - return make_can_msg(0x2e4, msg, 0, True) - - -def create_accel_command(accel, pcm_cancel, standstill_req): - # TODO: find the exact canceling bit - state = 0x40 if standstill_req else 0xC0 - state += pcm_cancel # this allows automatic restart from hold without driver cmd - - msg = struct.pack("!hBBBBB", accel, 0x63, state, 0x00, 0x00, 0x00) - - return make_can_msg(0x343, msg, 0, True) - -def create_fcw_command(fcw): - - msg = struct.pack("!BBBBBBBB", fcw<<4, 0x20, 0x00, 0x00, 0x10, 0x00, 0x80, 0x00) - - return make_can_msg(0x411, msg, 0, False) - - -def create_ui_command(steer, sound1, sound2): - msg = struct.pack("!BBBBBBBB", 0x54, 0x04 + steer + (sound2<<4), 0x0C, 0x00, - sound1, 0x2C, 0x38, 0x02) - return make_can_msg(0x412, msg, 0, False) + values = { + "STEER_REQUEST": steer_req, + "STEER_TORQUE_CMD": steer, + "COUNTER": raw_cnt, + "SET_ME_1": 1, + } + return packer.make_can_msg("STEERING_LKA", 0, values) + + +def create_accel_command(packer, accel, pcm_cancel, standstill_req): + # TODO: find the exact canceling bit that does not create a chime + values = { + "ACCEL_CMD": accel, + "SET_ME_X63": 0x63, + "SET_ME_1": 1, + "RELEASE_STANDSTILL": not standstill_req, + "CANCEL_REQ": pcm_cancel, + } + return packer.make_can_msg("ACC_CONTROL", 0, values) + + +def create_fcw_command(packer, fcw): + values = { + "FCW": fcw, + "SET_ME_X20": 0x20, + "SET_ME_X10": 0x10, + "SET_ME_X80": 0x80, + } + return packer.make_can_msg("ACC_HUD", 0, values) + + +def create_ui_command(packer, steer, sound1, sound2): + values = { + "RIGHT_LINE": 1, + "LEFT_LINE": 1, + "SET_ME_X0C": 0x0c, + "SET_ME_X2C": 0x2c, + "SET_ME_X38": 0x38, + "SET_ME_X02": 0x02, + "SET_ME_X01": 1, + "SET_ME_X01_2": 1, + "REPEATED_BEEPS": sound1, + "TWO_BEEPS": sound2, + "LDA_ALERT": steer, + } + return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index d8fa0c699e5453..d4929e7bc2c98b 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1,64 +1,160 @@ -class CAR: +from selfdrive.car import dbc_dict + +class CAR: PRIUS = "TOYOTA PRIUS 2017" - RAV4H = "TOYOTA RAV4 2017 HYBRID" + RAV4H = "TOYOTA RAV4 HYBRID 2017" RAV4 = "TOYOTA RAV4 2017" + COROLLA = "TOYOTA COROLLA 2017" + LEXUS_RXH = "LEXUS RX HYBRID 2017" + CHR = "TOYOTA C-HR 2018" + CHRH = "TOYOTA C-HR HYBRID 2018" + CAMRY = "TOYOTA CAMRY 2018" + CAMRYH = "TOYOTA CAMRY HYBRID 2018" + HIGHLANDER = "TOYOTA HIGHLANDER 2017" + HIGHLANDERH = "TOYOTA HIGHLANDER HYBRID 2018" + +class ECU: + CAM = 0 # camera + DSU = 1 # driving support unit + APGS = 2 # advanced parking guidance system -class ECU: - CAM = 0 # camera - DSU = 1 # driving support unit - APGS = 2 # advanced parking guidance system +# addr: (ecu, cars, bus, 1/freq*100, vl) +STATIC_MSGS = [ + (0x130, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 100, '\x00\x00\x00\x00\x00\x00\x38'), + (0x240, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x241, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x244, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x245, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x248, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x00\x00\x00\x00\x00\x01'), + (0x367, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 40, '\x06\x00'), + (0x414, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x00\x00\x00\x00\x00\x00\x17\x00'), + (0x466, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 100, '\x20\x20\xAD'), + (0x466, ECU.CAM, (CAR.COROLLA), 1, 100, '\x24\x20\xB1'), + (0x489, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), + (0x48a, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), + (0x48b, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x66\x06\x08\x0a\x02\x00\x00\x00'), + (0x4d3, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA), 0, 100, '\x1C\x00\x00\x01\x00\x00\x00\x00'), -# addr, [ecu, bus, 1/freq*100, vl] -STATIC_MSGS = {0x141: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 2, '\x00\x00\x00\x46'), - 0x128: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 3, '\xf4\x01\x90\x83\x00\x37'), + (0x128, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA), 1, 3, '\xf4\x01\x90\x83\x00\x37'), + (0x128, ECU.DSU, (CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 3, '\x03\x00\x20\x00\x00\x52'), + (0x141, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 2, '\x00\x00\x00\x46'), + (0x160, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 7, '\x00\x00\x08\x12\x01\x31\x9c\x51'), + (0x161, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA), 1, 7, '\x00\x1e\x00\x00\x00\x80\x07'), + (0X161, ECU.DSU, (CAR.HIGHLANDERH, CAR.HIGHLANDER), 1, 7, '\x00\x1e\x00\xd4\x00\x00\x5b'), + (0x283, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 3, '\x00\x00\x00\x00\x00\x00\x8c'), + (0x2E6, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, '\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), + (0x2E7, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, '\xa8\x9c\x31\x9c\x00\x00\x00\x02'), + (0x33E, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 20, '\x0f\xff\x26\x40\x00\x1f\x00'), + (0x344, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 5, '\x00\x00\x01\x00\x00\x00\x00\x50'), + (0x365, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.HIGHLANDERH), 0, 20, '\x00\x00\x00\x80\x03\x00\x08'), + (0x365, ECU.DSU, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER), 0, 20, '\x00\x00\x00\x80\xfc\x00\x08'), + (0x366, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.HIGHLANDERH), 0, 20, '\x00\x00\x4d\x82\x40\x02\x00'), + (0x366, ECU.DSU, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER), 0, 20, '\x00\x72\x07\xff\x09\xfe\x00'), + (0x470, ECU.DSU, (CAR.PRIUS, CAR.LEXUS_RXH), 1, 100, '\x00\x00\x02\x7a'), + (0x470, ECU.DSU, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.RAV4H), 1, 100, '\x00\x00\x01\x79'), + (0x4CB, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER), 0, 100, '\x0c\x00\x00\x00\x00\x00\x00\x00'), - 0x292: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 3, '\x00\x00\x00\x00\x00\x00\x00\x9e'), - 0x283: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 3, '\x00\x00\x00\x00\x00\x00\x8c'), - 0x2E6: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 3, '\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), - 0x2E7: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 3, '\xa8\x9c\x31\x9c\x00\x00\x00\x02'), + (0x292, ECU.APGS, (CAR.PRIUS), 0, 3, '\x00\x00\x00\x00\x00\x00\x00\x9e'), + (0x32E, ECU.APGS, (CAR.PRIUS), 0, 20, '\x00\x00\x00\x00\x00\x00\x00\x00'), + (0x396, ECU.APGS, (CAR.PRIUS), 0, 100, '\xBD\x00\x00\x00\x60\x0F\x02\x00'), + (0x43A, ECU.APGS, (CAR.PRIUS), 0, 100, '\x84\x00\x00\x00\x00\x00\x00\x00'), + (0x43B, ECU.APGS, (CAR.PRIUS), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), + (0x497, ECU.APGS, (CAR.PRIUS), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), + (0x4CC, ECU.APGS, (CAR.PRIUS), 0, 100, '\x0D\x00\x00\x00\x00\x00\x00\x00'), +] - 0x240: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x241: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x244: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x245: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x248: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x00\x00\x00\x00\x00\x01'), - 0x344: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 5, '\x00\x00\x01\x00\x00\x00\x00\x50'), +ECU_FINGERPRINT = { + ECU.CAM: 0x2e4, # steer torque cmd + ECU.DSU: 0x343, # accel cmd + ECU.APGS: 0x835, # angle cmd +} - 0x160: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 7, '\x00\x00\x08\x12\x01\x31\x9c\x51'), - 0x161: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 7, '\x00\x1e\x00\x00\x00\x80\x07'), - 0x32E: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 20, '\x00\x00\x00\x00\x00\x00\x00\x00'), - 0x33E: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 20, '\x0f\xff\x26\x40\x00\x1f\x00'), - 0x365: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 20, '\x00\x00\x00\x80\x03\x00\x08'), - 0x365: (ECU.DSU, (CAR.RAV4,), 0, 20, '\x00\x00\x00\x80\xfc\x00\x08'), - 0x366: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 20, '\x00\x00\x4d\x82\x40\x02\x00'), - 0x366: (ECU.DSU, (CAR.RAV4,), 0, 20, '\x00\x72\x07\xff\x09\xfe\x00'), +def check_ecu_msgs(fingerprint, ecu): + # return True if fingerprint contains messages normally sent by a given ecu + return ECU_FINGERPRINT[ecu] in fingerprint - 0x367: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 40, '\x06\x00'), - 0x414: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x17\x00'), - 0x489: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), - 0x48a: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), - 0x48b: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x66\x06\x08\x0a\x02\x00\x00\x00'), - 0x4d3: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x1C\x00\x00\x01\x00\x00\x00\x00'), - 0x130: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 100, '\x00\x00\x00\x00\x00\x00\x38'), - 0x466: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 100, '\x20\x20\xAD'), - 0x396: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\xBD\x00\x00\x00\x60\x0F\x02\x00'), - 0x43A: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x84\x00\x00\x00\x00\x00\x00\x00'), - 0x43B: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), - 0x497: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), - 0x4CC: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x0D\x00\x00\x00\x00\x00\x00\x00'), - 0x4CB: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x0c\x00\x00\x00\x00\x00\x00\x00'), - 0x470: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 1, 100, '\x00\x00\x02\x7a'), - } +FINGERPRINTS = { + CAR.RAV4: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 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, 951: 8, 955: 4, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 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, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 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, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.RAV4H: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 296: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 550: 8, 552: 4, 560: 7, 562: 4, 581: 5, 608: 8, 610: 5, 643: 7, 705: 8, 713: 8, 725: 2, 740: 5, 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, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 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, 1184: 8, 1185: 8, 1186: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1212: 8, 1227: 8, 1228: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 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, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # Chinese RAV4 + { + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 742: 8, 743: 8, 800: 8, 830: 7, 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, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1017: 8, 1041: 8, 1042: 8, 1043: 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, 1207: 8, 1227: 8, 1235: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 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, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8 + }], + CAR.PRIUS: [{ + 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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 869: 7, 870: 7, 871: 2, 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: 5, 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, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # Prius Prime + { + 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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 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, 974: 8, 975: 5, 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, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 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, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # Taiwanese Prius Prime + { + 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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 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, 974: 8, 975: 5, 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, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 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, 1175: 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, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.COROLLA: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 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 + }, + # Corolla LE 2017 + { + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 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, 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, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 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, 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, 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 + }], + CAR.CHR: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 705: 8, 740: 5, 800: 8, 810: 2, 812: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8 + }], + CAR.CHRH: [{ + 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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 800: 8, 810: 2, 812: 8, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 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: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.CAMRY: [ + #XLE and LE + { + 36: 8, 37: 8, 119: 6, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 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, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + #XSE and SE + { + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 888: 8, 889: 8, 891: 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, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.CAMRYH: [ + #LE + { + 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: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 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, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572:8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.HIGHLANDER: [{ + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 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, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 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 + }, + # 2017 Highlander Limited + { + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 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, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 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, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.HIGHLANDERH: [{ + 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, 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, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 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, 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, 1264: 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, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], +} +STEER_THRESHOLD = 100 -def check_ecu_msgs(fingerprint, candidate, ecu): - # return True if fingerprint contains messages normally sent by a given ecu - ecu_msgs = [x for x in STATIC_MSGS if (ecu == STATIC_MSGS[x][0] and - candidate in STATIC_MSGS[x][1] and - STATIC_MSGS[x][2] == 0)] +DBC = { + CAR.RAV4H: dbc_dict('toyota_rav4_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.RAV4: dbc_dict('toyota_rav4_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.PRIUS: dbc_dict('toyota_prius_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.COROLLA: dbc_dict('toyota_corolla_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.LEXUS_RXH: dbc_dict('lexus_rx_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.CHR: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CHRH: dbc_dict('toyota_chr_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CAMRY: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CAMRYH: dbc_dict('toyota_camry_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.HIGHLANDER: dbc_dict('toyota_highlander_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.HIGHLANDERH: dbc_dict('toyota_highlander_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), +} - return any(msg for msg in fingerprint if msg in ecu_msgs) +NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH] diff --git a/selfdrive/common/efd.c b/selfdrive/common/efd.c new file mode 100644 index 00000000000000..78a7c098949b56 --- /dev/null +++ b/selfdrive/common/efd.c @@ -0,0 +1,56 @@ +#include +#include + +#ifdef __linux__ +#include +#else +#include +#include +#define EVENT_IDENT 42 +#endif + +#include "efd.h" + + +int efd_init() { +#ifdef __linux__ + return eventfd(0, EFD_CLOEXEC); +#else + int fd = kqueue(); + assert(fd >= 0); + + struct kevent kev; + EV_SET(&kev, EVENT_IDENT, EVFILT_USER, EV_ADD | EV_CLEAR, 0, 0, NULL); + + struct timespec timeout = {0, 0}; + int err = kevent(fd, &kev, 1, NULL, 0, &timeout); + assert(err != -1); + + return fd; +#endif +} + +void efd_write(int fd) { +#ifdef __linux__ + eventfd_write(fd, 1); +#else + struct kevent kev; + EV_SET(&kev, EVENT_IDENT, EVFILT_USER, 0, NOTE_TRIGGER, 0, NULL); + + struct timespec timeout = {0, 0}; + int err = kevent(fd, &kev, 1, NULL, 0, &timeout); + assert(err != -1); +#endif +} + +void efd_clear(int fd) { +#ifdef __linux__ + eventfd_t efd_cnt; + eventfd_read(fd, &efd_cnt); +#else + struct kevent kev; + struct timespec timeout = {0, 0}; + int nfds = kevent(fd, NULL, 0, &kev, 1, &timeout); + assert(nfds != -1); +#endif +} diff --git a/selfdrive/common/efd.h b/selfdrive/common/efd.h new file mode 100644 index 00000000000000..056482ffa51f3e --- /dev/null +++ b/selfdrive/common/efd.h @@ -0,0 +1,17 @@ +#ifndef EFD_H +#define EFD_H + +#ifdef __cplusplus +extern "C" { +#endif + +// event fd: a semaphore that can be poll()'d +int efd_init(); +void efd_write(int fd); +void efd_clear(int fd); + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 0bee19b74e16d2..757c2a1ead46f0 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -56,8 +56,8 @@ extern "C" FramebufferState* framebuffer_init( status = SurfaceComposerClient::getDisplayInfo(s->dtoken, &s->dinfo); assert(status == 0); - int orientation = 3; // rotate framebuffer 270 degrees - //int orientation = 1; // rotate framebuffer 90 degrees + //int orientation = 3; // rotate framebuffer 270 degrees + int orientation = 1; // rotate framebuffer 90 degrees if(orientation == 1 || orientation == 3) { int temp = s->dinfo.h; s->dinfo.h = s->dinfo.w; diff --git a/selfdrive/common/ipc.c b/selfdrive/common/ipc.c new file mode 100644 index 00000000000000..8d391074786815 --- /dev/null +++ b/selfdrive/common/ipc.c @@ -0,0 +1,119 @@ +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ipc.h" + +int ipc_connect(const char* socket_path) { + int err; + + int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); + assert(sock >= 0); + struct sockaddr_un addr = { + .sun_family = AF_UNIX, + }; + snprintf(addr.sun_path, sizeof(addr.sun_path), "%s", socket_path); + err = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (err != 0) { + close(sock); + return -1; + } + + return sock; +} + +int ipc_bind(const char* socket_path) { + int err; + + unlink(socket_path); + + int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); + struct sockaddr_un addr = { + .sun_family = AF_UNIX, + }; + snprintf(addr.sun_path, sizeof(addr.sun_path), "%s", socket_path); + err = bind(sock, (struct sockaddr *)&addr, sizeof(addr)); + assert(err == 0); + + err = listen(sock, 3); + assert(err == 0); + + return sock; +} + + +int ipc_sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, + int *out_num_fds) { + int err; + + char control_buf[CMSG_SPACE(sizeof(int) * num_fds)]; + memset(control_buf, 0, CMSG_SPACE(sizeof(int) * num_fds)); + + struct iovec iov = { + .iov_base = buf, + .iov_len = buf_size, + }; + struct msghdr msg = { + .msg_iov = &iov, + .msg_iovlen = 1, + }; + + if (num_fds > 0) { + assert(fds); + + msg.msg_control = control_buf; + msg.msg_controllen = CMSG_SPACE(sizeof(int) * num_fds); + } + + if (send) { + if (num_fds) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + cmsg->cmsg_level = SOL_SOCKET; + cmsg->cmsg_type = SCM_RIGHTS; + cmsg->cmsg_len = CMSG_LEN(sizeof(int) * num_fds); + memcpy(CMSG_DATA(cmsg), fds, sizeof(int) * num_fds); + // printf("send clen %d -> %d\n", num_fds, cmsg->cmsg_len); + } + return sendmsg(fd, &msg, 0); + } else { + int r = recvmsg(fd, &msg, 0); + if (r < 0) return r; + + int recv_fds = 0; + if (msg.msg_controllen > 0) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + assert(cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SCM_RIGHTS); + recv_fds = (cmsg->cmsg_len - CMSG_LEN(0)); + assert(recv_fds > 0 && (recv_fds % sizeof(int)) == 0); + recv_fds /= sizeof(int); + // printf("recv clen %d -> %d\n", cmsg->cmsg_len, recv_fds); + // assert(cmsg->cmsg_len == CMSG_LEN(sizeof(int) * num_fds)); + + assert(fds && recv_fds <= num_fds); + memcpy(fds, CMSG_DATA(cmsg), sizeof(int) * recv_fds); + } + + if (msg.msg_flags) { + for (int i=0; i + +#ifdef __cplusplus +extern "C" { +#endif + +int ipc_connect(const char* socket_path); +int ipc_bind(const char* socket_path); +int ipc_sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, + int *out_num_fds); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif \ No newline at end of file diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index 5b0d216bdd873c..7bbcf5fad11c60 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -1,15 +1,20 @@ -#include "selfdrive/common/params.h" - -#include "selfdrive/common/util.h" +#include "common/params.h" #ifndef _GNU_SOURCE #define _GNU_SOURCE #endif // _GNU_SOURCE -#include -#include -#include #include +#include +#include +#include +#include + +#include +#include + +#include "common/util.h" +#include "common/utilpp.h" namespace { @@ -152,3 +157,40 @@ void read_db_value_blocking(const char* params_path, const char* key, } } } + +int read_db_all(const char* params_path, std::map *params) { + int err = 0; + + if (params_path == NULL) { + params_path = default_params_path; + } + + std::string lock_path = util::string_format("%s/.lock", params_path); + + int lock_fd = open(lock_path.c_str(), 0); + if (lock_fd < 0) return -1; + + err = flock(lock_fd, LOCK_EX); + if (err < 0) return err; + + std::string key_path = util::string_format("%s/d", params_path); + DIR *d = opendir(key_path.c_str()); + if (!d) { + close(lock_fd); + return -1; + } + + struct dirent *de = NULL; + while ((de = readdir(d))) { + if (!isalnum(de->d_name[0])) continue; + std::string key = std::string(de->d_name); + std::string value = util::read_file(util::string_format("%s/%s", key_path.c_str(), key.c_str())); + + (*params)[key] = value; + } + + closedir(d); + + close(lock_fd); + return 0; +} diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h index bd4d86dcfee97c..299dcccd0a412d 100644 --- a/selfdrive/common/params.h +++ b/selfdrive/common/params.h @@ -32,4 +32,10 @@ void read_db_value_blocking(const char* params_path, const char* key, } // extern "C" #endif +#ifdef __cplusplus +#include +#include +int read_db_all(const char* params_path, std::map *params); +#endif + #endif // _SELFDRIVE_COMMON_PARAMS_H_ diff --git a/selfdrive/common/touch.c b/selfdrive/common/touch.c index a6dc226053e14a..f21fac8f07afd5 100644 --- a/selfdrive/common/touch.c +++ b/selfdrive/common/touch.c @@ -24,15 +24,14 @@ static int find_dev() { int fd = openat(dirfd(dir), de->d_name, O_RDONLY); assert(fd >= 0); - char name[128] = {0}; - err = ioctl(fd, EVIOCGNAME(sizeof(name) - 1), &name); + unsigned char ev_bits[KEY_MAX / 8 + 1]; + err = ioctl(fd, EVIOCGBIT(EV_ABS, sizeof(ev_bits)), ev_bits); assert(err >= 0); - unsigned long ev_bits[8] = {0}; - err = ioctl(fd, EVIOCGBIT(0, sizeof(ev_bits)), ev_bits); - assert(err >= 0); - - if (strncmp(name, "synaptics", 9) == 0 && ev_bits[0] == 0xb) { + const int x_key = ABS_MT_POSITION_X / 8; + const int y_key = ABS_MT_POSITION_Y / 8; + if ((ev_bits[x_key] & (ABS_MT_POSITION_X - x_key)) && + (ev_bits[y_key] & (ABS_MT_POSITION_Y - y_key))) { ret = fd; break; } @@ -48,7 +47,7 @@ void touch_init(TouchState *s) { assert(s->fd >= 0); } -int touch_poll(TouchState *s, int* out_x, int* out_y) { +int touch_poll(TouchState *s, int* out_x, int* out_y, int timeout) { assert(out_x && out_y); bool up = false; while (true) { @@ -56,7 +55,7 @@ int touch_poll(TouchState *s, int* out_x, int* out_y) { .fd = s->fd, .events = POLLIN, }}; - int err = poll(polls, 1, 0); + int err = poll(polls, 1, timeout); if (err < 0) { return -1; } @@ -77,21 +76,16 @@ int touch_poll(TouchState *s, int* out_x, int* out_y) { } else if (event.code == ABS_MT_POSITION_Y) { s->last_y = event.value; } - break; - case EV_KEY: - if (event.code == BTN_TOOL_FINGER && event.value == 0) { - // finger up - up = true; - } + up = true; break; default: break; } } if (up) { - // adjust for landscape - *out_x = 1920 - s->last_y; - *out_y = s->last_x; + // adjust for flippening + *out_x = s->last_y; + *out_y = 1080 - s->last_x; } return up; } diff --git a/selfdrive/common/touch.h b/selfdrive/common/touch.h index 3767c06dc340c7..c2bb6dfeced30c 100644 --- a/selfdrive/common/touch.h +++ b/selfdrive/common/touch.h @@ -11,7 +11,7 @@ typedef struct TouchState { } TouchState; void touch_init(TouchState *s); -int touch_poll(TouchState *s, int *out_x, int *out_y); +int touch_poll(TouchState *s, int *out_x, int *out_y, int timeout); #ifdef __cplusplus } diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c index 172345869ec8a4..6f8f0a9a6cf186 100644 --- a/selfdrive/common/util.c +++ b/selfdrive/common/util.c @@ -2,9 +2,12 @@ #include #include #include +#include #ifdef __linux__ #include +#include +#include #endif void* read_file(const char* path, size_t* out_len) { @@ -39,3 +42,17 @@ void set_thread_name(const char* name) { prctl(PR_SET_NAME, (unsigned long)name, 0, 0, 0); #endif } + +int set_realtime_priority(int level) { +#ifdef __linux__ + + long tid = syscall(SYS_gettid); + + // should match python using chrt + struct sched_param sa; + memset(&sa, 0, sizeof(sa)); + sa.sched_priority = level; + return sched_setscheduler(tid, SCHED_FIFO, &sa); +#endif +} + diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index ce18068bbe7c7d..65dde16e24082e 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -24,6 +24,8 @@ #define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) +#define ALIGN(x, align) (((x) + (align)-1) & ~((align)-1)) + #ifdef __cplusplus extern "C" { #endif @@ -36,6 +38,8 @@ void* read_file(const char* path, size_t* out_len); void set_thread_name(const char* name); +int set_realtime_priority(int level); + #ifdef __cplusplus } #endif diff --git a/selfdrive/common/utilpp.h b/selfdrive/common/utilpp.h index bc1b2fd267d966..e374c5c256f772 100644 --- a/selfdrive/common/utilpp.h +++ b/selfdrive/common/utilpp.h @@ -9,10 +9,6 @@ #include #include -#ifdef __x86_64 -#include -#endif - namespace util { inline bool starts_with(std::string s, std::string prefix) { @@ -56,13 +52,13 @@ inline std::string dir_name(std::string const & path) { } inline std::string readlink(std::string path) { - char buff[PATH_MAX]; - ssize_t len = ::readlink(path.c_str(), buff, sizeof(buff)-1); - if (len != -1) { - buff[len] = '\0'; - return std::string(buff); - } - return ""; + char buff[4096]; + ssize_t len = ::readlink(path.c_str(), buff, sizeof(buff)-1); + if (len != -1) { + buff[len] = '\0'; + return std::string(buff); + } + return ""; } } diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index 4cf48d2e1ffc45..617c8189cba23d 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.4.0.1-openpilot" +#define COMMA_VERSION "0.5.6-release" diff --git a/selfdrive/common/visionbuf.h b/selfdrive/common/visionbuf.h new file mode 100644 index 00000000000000..3457f6dff33949 --- /dev/null +++ b/selfdrive/common/visionbuf.h @@ -0,0 +1,39 @@ +#ifndef IONBUF_H +#define IONBUF_H + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct VisionBuf { + size_t len; + void* addr; + int handle; + int fd; + + cl_context ctx; + cl_device_id device_id; + cl_mem buf_cl; + cl_command_queue copy_q; +} VisionBuf; + +#define VISIONBUF_SYNC_FROM_DEVICE 0 +#define VISIONBUF_SYNC_TO_DEVICE 1 + +VisionBuf visionbuf_allocate(size_t len); +VisionBuf visionbuf_allocate_cl(size_t len, cl_device_id device_id, cl_context ctx, cl_mem *out_mem); +cl_mem visionbuf_to_cl(const VisionBuf* buf, cl_device_id device_id, cl_context ctx); +void visionbuf_sync(const VisionBuf* buf, int dir); +void visionbuf_free(const VisionBuf* buf); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/common/visionbuf_ion.c b/selfdrive/common/visionbuf_ion.c new file mode 100644 index 00000000000000..724e75e9b0c0d5 --- /dev/null +++ b/selfdrive/common/visionbuf_ion.c @@ -0,0 +1,141 @@ +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include "visionbuf.h" + + +// just hard-code these for convenience +// size_t device_page_size = 0; +// clGetDeviceInfo(device_id, CL_DEVICE_PAGE_SIZE_QCOM, +// sizeof(device_page_size), &device_page_size, +// NULL); + +// size_t padding_cl = 0; +// clGetDeviceInfo(device_id, CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM, +// sizeof(padding_cl), &padding_cl, +// NULL); +#define DEVICE_PAGE_SIZE_CL 4096 +#define PADDING_CL 0 + +static int ion_fd = -1; +static void ion_init() { + if (ion_fd == -1) { + ion_fd = open("/dev/ion", O_RDWR | O_NONBLOCK); + } +} + +VisionBuf visionbuf_allocate(size_t len) { + int err; + + ion_init(); + + struct ion_allocation_data ion_alloc = {0}; + ion_alloc.len = len + PADDING_CL; + ion_alloc.align = 4096; + ion_alloc.heap_id_mask = 1 << ION_IOMMU_HEAP_ID; + ion_alloc.flags = ION_FLAG_CACHED; + + err = ioctl(ion_fd, ION_IOC_ALLOC, &ion_alloc); + assert(err == 0); + + struct ion_fd_data ion_fd_data = {0}; + ion_fd_data.handle = ion_alloc.handle; + err = ioctl(ion_fd, ION_IOC_SHARE, &ion_fd_data); + assert(err == 0); + + void *addr = mmap(NULL, ion_alloc.len, + PROT_READ | PROT_WRITE, + MAP_SHARED, ion_fd_data.fd, 0); + assert(addr != MAP_FAILED); + + memset(addr, 0, ion_alloc.len); + + return (VisionBuf){ + .len = len, + .addr = addr, + .handle = ion_alloc.handle, + .fd = ion_fd_data.fd, + }; +} + +VisionBuf visionbuf_allocate_cl(size_t len, cl_device_id device_id, cl_context ctx, cl_mem *out_mem) { + VisionBuf r = visionbuf_allocate(len); + *out_mem = visionbuf_to_cl(&r, device_id, ctx); + return r; +} + +cl_mem visionbuf_to_cl(const VisionBuf* buf, cl_device_id device_id, cl_context ctx) { + int err = 0; + + assert(((uintptr_t)buf->addr % DEVICE_PAGE_SIZE_CL) == 0); + + cl_mem_ion_host_ptr ion_cl = {0}; + ion_cl.ext_host_ptr.allocation_type = CL_MEM_ION_HOST_PTR_QCOM; + ion_cl.ext_host_ptr.host_cache_policy = CL_MEM_HOST_UNCACHED_QCOM; + ion_cl.ion_filedesc = buf->fd; + ion_cl.ion_hostptr = buf->addr; + + cl_mem mem = clCreateBuffer(ctx, + CL_MEM_USE_HOST_PTR | CL_MEM_EXT_HOST_PTR_QCOM, + buf->len, &ion_cl, &err); + assert(err == 0); + + return mem; +} + +void visionbuf_sync(const VisionBuf* buf, int dir) { + int err; + + struct ion_fd_data fd_data = {0}; + fd_data.fd = buf->fd; + err = ioctl(ion_fd, ION_IOC_IMPORT, &fd_data); + assert(err == 0); + + struct ion_flush_data flush_data = {0}; + flush_data.handle = fd_data.handle; + flush_data.vaddr = buf->addr; + flush_data.offset = 0; + flush_data.length = buf->len; + + // ION_IOC_INV_CACHES ~= DMA_FROM_DEVICE + // ION_IOC_CLEAN_CACHES ~= DMA_TO_DEVICE + // ION_IOC_CLEAN_INV_CACHES ~= DMA_BIDIRECTIONAL + + struct ion_custom_data custom_data = {0}; + + switch (dir) { + case VISIONBUF_SYNC_FROM_DEVICE: + custom_data.cmd = ION_IOC_INV_CACHES; + break; + case VISIONBUF_SYNC_TO_DEVICE: + custom_data.cmd = ION_IOC_CLEAN_CACHES; + break; + default: + assert(0); + } + + custom_data.arg = (unsigned long)&flush_data; + err = ioctl(ion_fd, ION_IOC_CUSTOM, &custom_data); + assert(err == 0); + + struct ion_handle_data handle_data = {0}; + handle_data.handle = fd_data.handle; + err = ioctl(ion_fd, ION_IOC_FREE, &handle_data); + assert(err == 0); +} + +void visionbuf_free(const VisionBuf* buf) { + struct ion_handle_data handle_data = { + .handle = buf->handle, + }; + int ret = ioctl(ion_fd, ION_IOC_FREE, &handle_data); + assert(ret == 0); +} diff --git a/selfdrive/common/visionimg.cc b/selfdrive/common/visionimg.cc new file mode 100644 index 00000000000000..8179166e1c7759 --- /dev/null +++ b/selfdrive/common/visionimg.cc @@ -0,0 +1,114 @@ +#include + +#ifdef QCOM +#include +#include +#include +#include + +#include +#define GL_GLEXT_PROTOTYPES +#include + +#include +#define EGL_EGLEXT_PROTOTYPES +#include + +#endif + +#include "common/util.h" +#include "common/visionbuf.h" + +#include "common/visionimg.h" + +#ifdef QCOM + +using namespace android; + +// from libadreno_utils.so +extern "C" void compute_aligned_width_and_height(int width, + int height, + int bpp, + int tile_mode, + int raster_mode, + int padding_threshold, + int *aligned_w, + int *aligned_h); +#endif + +void visionimg_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h) { +#ifdef QCOM + compute_aligned_width_and_height(ALIGN(width, 32), ALIGN(height, 32), 3, 0, 0, 512, aligned_w, aligned_h); +#else + *aligned_w = width; *aligned_h = height; +#endif +} + +VisionImg visionimg_alloc_rgb24(int width, int height, VisionBuf *out_buf) { + int aligned_w = 0, aligned_h = 0; + visionimg_compute_aligned_width_and_height(width, height, &aligned_w, &aligned_h); + + int stride = aligned_w * 3; + size_t size = aligned_w * aligned_h * 3; + + VisionBuf buf = visionbuf_allocate(size); + + *out_buf = buf; + + return (VisionImg){ + .fd = buf.fd, + .format = VISIONIMG_FORMAT_RGB24, + .width = width, + .height = height, + .stride = stride, + .size = size, + .bpp = 3, + }; +} + +#ifdef QCOM + +EGLClientBuffer visionimg_to_egl(const VisionImg *img) { + assert((img->size % img->stride) == 0); + assert((img->stride % img->bpp) == 0); + + int format = 0; + if (img->format == VISIONIMG_FORMAT_RGB24) { + format = HAL_PIXEL_FORMAT_RGB_888; + } else { + assert(false); + } + + private_handle_t* hnd = new private_handle_t(img->fd, img->size, + private_handle_t::PRIV_FLAGS_USES_ION|private_handle_t::PRIV_FLAGS_FRAMEBUFFER, + 0, format, + img->stride/img->bpp, img->size/img->stride, + img->width, img->height); + + GraphicBuffer* gb = new GraphicBuffer(img->width, img->height, (PixelFormat)format, + GraphicBuffer::USAGE_HW_TEXTURE, img->stride/img->bpp, hnd, false); + + return (EGLClientBuffer) gb->getNativeBuffer(); +} + +GLuint visionimg_to_gl(const VisionImg *img) { + + EGLClientBuffer buf = visionimg_to_egl(img); + + EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(display != EGL_NO_DISPLAY); + + EGLint img_attrs[] = { EGL_IMAGE_PRESERVED_KHR, EGL_TRUE, EGL_NONE }; + EGLImageKHR image = eglCreateImageKHR(display, EGL_NO_CONTEXT, + EGL_NATIVE_BUFFER_ANDROID, buf, img_attrs); + assert(image != EGL_NO_IMAGE_KHR); + + GLuint tex = 0; + glGenTextures(1, &tex); + glBindTexture(GL_TEXTURE_2D, tex); + glEGLImageTargetTexture2DOES(GL_TEXTURE_2D, image); + + return tex; +} + +#endif diff --git a/selfdrive/common/visionimg.h b/selfdrive/common/visionimg.h new file mode 100644 index 00000000000000..9fabb6054f6dd3 --- /dev/null +++ b/selfdrive/common/visionimg.h @@ -0,0 +1,38 @@ +#ifndef VISIONIMG_H +#define VISIONIMG_H + +#ifdef QCOM +#include +#include +#include +#endif + +#include "common/visionbuf.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#define VISIONIMG_FORMAT_RGB24 1 + +typedef struct VisionImg { + int fd; + int format; + int width, height, stride; + int bpp; + size_t size; +} VisionImg; + +void visionimg_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h); +VisionImg visionimg_alloc_rgb24(int width, int height, VisionBuf *out_buf); + +#ifdef QCOM +EGLClientBuffer visionimg_to_egl(const VisionImg *img); +GLuint visionimg_to_gl(const VisionImg *img); +#endif + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/selfdrive/common/visionipc.c b/selfdrive/common/visionipc.c index 4299f512f9a04e..314f7d0a55c712 100644 --- a/selfdrive/common/visionipc.c +++ b/selfdrive/common/visionipc.c @@ -10,6 +10,8 @@ #include #include +#include "ipc.h" + #include "visionipc.h" typedef struct VisionPacketWire { @@ -18,95 +20,14 @@ typedef struct VisionPacketWire { } VisionPacketWire; int vipc_connect() { - int err; - - int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); - assert(sock >= 0); - struct sockaddr_un addr = { - .sun_family = AF_UNIX, - .sun_path = VIPC_SOCKET_PATH, - }; - err = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); - if (err != 0) { - close(sock); - return -1; - } - - return sock; + return ipc_connect(VIPC_SOCKET_PATH); } -static int sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, - int *out_num_fds) { - int err; - - char control_buf[CMSG_SPACE(sizeof(int) * num_fds)]; - memset(control_buf, 0, CMSG_SPACE(sizeof(int) * num_fds)); - - struct iovec iov = { - .iov_base = buf, - .iov_len = buf_size, - }; - struct msghdr msg = { - .msg_iov = &iov, - .msg_iovlen = 1, - }; - - if (num_fds > 0) { - assert(fds); - - msg.msg_control = control_buf; - msg.msg_controllen = CMSG_SPACE(sizeof(int) * num_fds); - } - - if (send) { - if (num_fds) { - struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); - assert(cmsg); - cmsg->cmsg_level = SOL_SOCKET; - cmsg->cmsg_type = SCM_RIGHTS; - cmsg->cmsg_len = CMSG_LEN(sizeof(int) * num_fds); - memcpy(CMSG_DATA(cmsg), fds, sizeof(int) * num_fds); - // printf("send clen %d -> %d\n", num_fds, cmsg->cmsg_len); - } - return sendmsg(fd, &msg, 0); - } else { - int r = recvmsg(fd, &msg, 0); - if (r < 0) return r; - - int recv_fds = 0; - if (msg.msg_controllen > 0) { - struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); - assert(cmsg); - assert(cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SCM_RIGHTS); - recv_fds = (cmsg->cmsg_len - CMSG_LEN(0)); - assert(recv_fds > 0 && (recv_fds % sizeof(int)) == 0); - recv_fds /= sizeof(int); - // printf("recv clen %d -> %d\n", cmsg->cmsg_len, recv_fds); - // assert(cmsg->cmsg_len == CMSG_LEN(sizeof(int) * num_fds)); - - assert(fds && recv_fds <= num_fds); - memcpy(fds, CMSG_DATA(cmsg), sizeof(int) * recv_fds); - } - - if (msg.msg_flags) { - for (int i=0; itype, .d = p2->d, }; - return sendrecv_with_fds(true, fd, (void*)&p, sizeof(p), (int*)p2->fds, p2->num_fds, NULL); + return ipc_sendrecv_with_fds(true, fd, (void*)&p, sizeof(p), (int*)p2->fds, p2->num_fds, NULL); } void vipc_bufs_load(VIPCBuf *bufs, const VisionStreamBufs *stream_bufs, @@ -193,6 +114,21 @@ int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, Visi return 0; } +void visionstream_release(VisionStream *s) { + int err; + if (s->last_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = s->last_type, + .idx = s->last_idx, + }} + }; + err = vipc_send(s->ipc_fd, &rep); + s->last_idx = -1; + } +} + VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { int err; @@ -207,7 +143,7 @@ VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { VisionPacket rep = { .type = VIPC_STREAM_RELEASE, .d = { .stream_rel = { - .type = rp.d.stream_acq.type, + .type = s->last_type, .idx = s->last_idx, }} }; @@ -217,6 +153,7 @@ VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { } } + s->last_type = rp.d.stream_acq.type; s->last_idx = rp.d.stream_acq.idx; assert(s->last_idx < s->num_bufs); @@ -228,6 +165,20 @@ VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { } void visionstream_destroy(VisionStream *s) { + int err; + + if (s->last_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = s->last_type, + .idx = s->last_idx, + }} + }; + err = vipc_send(s->ipc_fd, &rep); + s->last_idx = -1; + } + for (int i=0; inum_bufs; i++) { if (s->bufs[i].addr) { munmap(s->bufs[i].addr, s->bufs[i].len); diff --git a/selfdrive/common/visionipc.h b/selfdrive/common/visionipc.h index 24b882340fea87..4844a71b1d756b 100644 --- a/selfdrive/common/visionipc.h +++ b/selfdrive/common/visionipc.h @@ -21,9 +21,10 @@ typedef enum VisionIPCPacketType { } VisionIPCPacketType; typedef enum VisionStreamType { - VISION_STREAM_UI_BACK, - VISION_STREAM_UI_FRONT, + VISION_STREAM_RGB_BACK, + VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV, + VISION_STREAM_YUV_FRONT, VISION_STREAM_MAX, } VisionStreamType; @@ -48,7 +49,9 @@ typedef struct VisionStreamBufs { } VisionStreamBufs; typedef struct VIPCBufExtra { - uint32_t frame_id; // only for yuv + // only for yuv + uint32_t frame_id; + uint64_t timestamp_eof; } VIPCBufExtra; typedef union VisionPacketData { @@ -92,12 +95,14 @@ void vipc_bufs_load(VIPCBuf *bufs, const VisionStreamBufs *stream_bufs, typedef struct VisionStream { int ipc_fd; int last_idx; + int last_type; int num_bufs; VisionStreamBufs bufs_info; VIPCBuf *bufs; } VisionStream; int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info); +void visionstream_release(VisionStream *s); VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra); void visionstream_destroy(VisionStream *s); diff --git a/selfdrive/config.py b/selfdrive/config.py index 3488a43816075c..751a84e285f52c 100644 --- a/selfdrive/config.py +++ b/selfdrive/config.py @@ -1,6 +1,7 @@ import numpy as np class Conversions: + #Speed MPH_TO_KPH = 1.609344 KPH_TO_MPH = 1. / MPH_TO_KPH MS_TO_KPH = 3.6 @@ -9,49 +10,15 @@ class Conversions: MPH_TO_MS = MPH_TO_KPH * KPH_TO_MS MS_TO_KNOTS = 1.9438 KNOTS_TO_MS = 1. / MS_TO_KNOTS + #Angle DEG_TO_RAD = np.pi/180. RAD_TO_DEG = 1. / DEG_TO_RAD + #Mass + LB_TO_KG = 0.453592 - # Car decode decimal minutes into decimal degrees, can work with numpy arrays as input - @staticmethod - def dm2d(dm): - degs = np.round(dm/100.) - mins = dm - degs*100. - return degs + mins/60. - - -# Car button codes -# TODO: this is Honda specific, move to honda/interface.py -class CruiseButtons: - RES_ACCEL = 4 - DECEL_SET = 3 - CANCEL = 2 - MAIN = 1 RADAR_TO_CENTER = 2.7 # RADAR is ~ 2.7m ahead from center of car -# Image params for color cam on acura, calibrated on pre las vegas drive (2016-05-21) -class ImageParams: - def __init__(self): - self.SX_R = 160 # top left corner pixel shift of the visual region considered by the model - self.SY_R = 180 # top left corner pixel shift of the visual region considered by the model - self.VPX_R = 319 # vanishing point reference, as calibrated in Vegas drive - self.VPY_R = 201 # vanishing point reference, as calibrated in Vegas drive - self.X = 320 # pixel length of image for model - self.Y = 160 # pixel length of image for model - self.SX = self.SX_R # current visual region with shift - self.SY = self.SY_R # current visual region with shift - self.VPX = self.VPX_R # current vanishing point with shift - self.VPY = self.VPY_R # current vanishing point with shift - def shift(self, shift): - def to_int(fl): - return int(round(fl)) - # shift comes from calibration and says how much to shift the viual region - self.SX = self.SX_R + to_int(shift[0]) # current visual region with shift - self.SY = self.SY_R + to_int(shift[1]) # current visual region with shift - self.VPX = self.VPX_R + to_int(shift[0]) # current vanishing point with shift - self.VPY = self.VPY_R + to_int(shift[1]) # current vanishing point with shift - class UIParams: lidar_x, lidar_y, lidar_zoom = 384, 960, 6 lidar_car_x, lidar_car_y = lidar_x/2., lidar_y/1.1 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index df27d6322a01ad..5a4b7ef4dda41a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -1,62 +1,62 @@ #!/usr/bin/env python -import json -from copy import copy +import gc import zmq +import json + from cereal import car, log from common.numpy_fast import clip from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper from common.profiler import Profiler from common.params import Params + import selfdrive.messaging as messaging from selfdrive.config import Conversions as CV from selfdrive.services import service_list -from selfdrive.car import get_car +from selfdrive.car.car_helpers import get_car from selfdrive.controls.lib.planner import Planner from selfdrive.controls.lib.drive_helpers import learn_angle_offset, \ get_events, \ create_event, \ - EventTypes as ET + EventTypes as ET, \ + update_v_cruise, \ + initialize_v_cruise from selfdrive.controls.lib.longcontrol import LongControl, STARTING_TARGET_SPEED from selfdrive.controls.lib.latcontrol import LatControl from selfdrive.controls.lib.alertmanager import AlertManager from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.controls.lib.driver_monitor import DriverStatus +from selfdrive.locationd.calibration_values import Calibration, Filter - -V_CRUISE_MAX = 144 -V_CRUISE_MIN = 8 -V_CRUISE_DELTA = 8 -V_CRUISE_ENABLE_MIN = 40 - -AWARENESS_TIME = 360. # 6 minutes limit without user touching steering wheels -AWARENESS_PRE_TIME = 20. # a first alert is issued 20s before start decelerating the car - +ThermalStatus = log.ThermalData.ThermalStatus State = log.Live100Data.ControlState -class Calibration: - UNCALIBRATED = 0 - CALIBRATED = 1 - INVALID = 2 - -# True when actuators are controlled def isActive(state): + """Check if the actuators are enabled""" return state in [State.enabled, State.softDisabling] -# True if system is engaged def isEnabled(state): + """Check if openpilot is engaged""" return (isActive(state) or state == State.preEnabled) -def data_sample(CI, CC, thermal, calibration, health, poller, cal_status, overtemp, free_space): +def data_sample(CI, CC, thermal, calibration, health, driver_monitor, gps_location, + poller, cal_status, cal_perc, overtemp, free_space, low_battery, + driver_status, geofence, state, mismatch_counter, params): + """Receive data from sockets and create events for battery, temperature and disk space""" - # *** read can and compute car states *** + # Update carstate from CAN and create events CS = CI.update(CC) events = list(CS.events) + enabled = isEnabled(state) + # Receive from sockets td = None cal = None hh = None + dm = None + gps = None for socket, event in poller.poll(0): if socket is thermal: @@ -65,83 +65,97 @@ def data_sample(CI, CC, thermal, calibration, health, poller, cal_status, overte cal = messaging.recv_one(socket) elif socket is health: hh = messaging.recv_one(socket) + elif socket is driver_monitor: + dm = messaging.recv_one(socket) + elif socket is gps_location: + gps = messaging.recv_one(socket) - # *** thermal checking logic *** - # thermal data, checked every second if td is not None: - # CPU overtemp above 95 deg - overtemp_proc = any(t > 950 for t in - (td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2, - td.thermal.cpu3, td.thermal.mem, td.thermal.gpu)) - overtemp_bat = td.thermal.bat > 50000 # 50c - overtemp = overtemp_proc or overtemp_bat - - # under 15% of space free no enable allowed - free_space = td.thermal.freeSpace < 0.15 + overtemp = td.thermal.thermalStatus >= ThermalStatus.red + free_space = td.thermal.freeSpace < 0.15 # under 15% of space free no enable allowed + low_battery = td.thermal.batteryPercent < 1 # at zero percent battery, OP should not be allowed + # Create events for battery, temperature and disk space + if low_battery: + events.append(create_event('lowBattery', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if overtemp: events.append(create_event('overheat', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if free_space: events.append(create_event('outOfSpace', [ET.NO_ENTRY])) - # *** read calibration status *** + # Handle calibration if cal is not None: cal_status = cal.liveCalibration.calStatus + cal_perc = cal.liveCalibration.calPerc if cal_status != Calibration.CALIBRATED: if cal_status == Calibration.UNCALIBRATED: - events.append(create_event('calibrationInProgress', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + events.append(create_event('calibrationIncomplete', [ET.NO_ENTRY, ET.SOFT_DISABLE, ET.PERMANENT])) else: events.append(create_event('calibrationInvalid', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - # *** health checking logic *** + # When the panda and controlsd do not agree on controls_allowed + # we want to disengage openpilot. However the status from the panda goes through + # another socket than the CAN messages, therefore one can arrive earlier than the other. + # Therefore we allow a mismatch for two samples, then we trigger the disengagement. + if not enabled: + mismatch_counter = 0 + if hh is not None: controls_allowed = hh.health.controlsAllowed - if not controls_allowed: + if not controls_allowed and enabled: + mismatch_counter += 1 + if mismatch_counter >= 2: events.append(create_event('controlsMismatch', [ET.IMMEDIATE_DISABLE])) - return CS, events, cal_status, overtemp, free_space + # Driver monitoring + if dm is not None: + driver_status.get_pose(dm.driverMonitoring, params) + + # Geofence + if geofence is not None and gps is not None: + geofence.update_geofence_status(gps.gpsLocationExternal, params) + if geofence is not None and not geofence.in_geofence: + events.append(create_event('geofence', [ET.NO_ENTRY, ET.WARNING])) + + return CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter -def calc_plan(CS, events, PL, LoC, v_cruise_kph, awareness_status): - # plan runs always, independently of the state - plan_packet = PL.update(CS, LoC, v_cruise_kph, awareness_status < -0.) - plan = plan_packet.plan - plan_ts = plan_packet.logMonoTime +def calc_plan(CS, CP, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence): + """Calculate a longitudinal plan using MPC""" - # add events from planner - events += list(plan.events) + # Slow down when based on driver monitoring or geofence + force_decel = driver_status.awareness < 0. or (geofence is not None and not geofence.in_geofence) - # disable if lead isn't close when system is active and brake is pressed to avoid - # unexpected vehicle accelerations - if CS.brakePressed and plan.vTargetFuture >= STARTING_TARGET_SPEED: - events.append(create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + # Update planner + plan_packet = PL.update(CS, LaC, LoC, v_cruise_kph, force_decel) + plan = plan_packet.plan + plan_ts = plan_packet.logMonoTime + events += list(plan.events) - return plan, plan_ts + # Only allow engagement with brake pressed when stopped behind another stopped car + if CS.brakePressed and plan.vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: + events.append(create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + + return plan, plan_ts def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM): - # compute conditional state transitions and execute actions on state transitions + """Compute conditional state transitions and execute actions on state transitions""" enabled = isEnabled(state) - # handle button presses. TODO: this should be in state_control, but a decelCruise press - # would have the effect of both enabling and changing speed is checked after the state transition v_cruise_kph_last = v_cruise_kph - for b in CS.buttonEvents: - if not CP.enableCruise and enabled and not b.pressed: - if b.type == "accelCruise": - v_cruise_kph -= (v_cruise_kph % V_CRUISE_DELTA) - V_CRUISE_DELTA - elif b.type == "decelCruise": - v_cruise_kph -= (v_cruise_kph % V_CRUISE_DELTA) + V_CRUISE_DELTA - v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) + + # if stock cruise is completely disabled, then we can use our own set speed logic + if not CP.enableCruise: + v_cruise_kph = update_v_cruise(v_cruise_kph, CS.buttonEvents, enabled) + elif CP.enableCruise and CS.cruiseState.enabled: + v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH # decrease the soft disable timer at every step, as it's reset on # entrance in SOFT_DISABLING state soft_disable_timer = max(0, soft_disable_timer - 1) - # ***** handle state transitions ***** - # DISABLED if state == State.disabled: if get_events(events, [ET.ENABLE]): @@ -155,8 +169,7 @@ def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM else: state = State.enabled AM.add("enable", enabled) - # on activation, let's always set v_cruise from where we are, even if PCM ACC is active - v_cruise_kph = int(round(max(CS.vEgo * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN))) + v_cruise_kph = initialize_v_cruise(CS.vEgo, CS.buttonEvents, v_cruise_kph_last) # ENABLED elif state == State.enabled: @@ -171,7 +184,7 @@ def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM elif get_events(events, [ET.SOFT_DISABLE]): state = State.softDisabling - soft_disable_timer = 300 # 3s TODO: use rate + soft_disable_timer = 300 # 3s for e in get_events(events, [ET.SOFT_DISABLE]): AM.add(e, enabled) @@ -190,6 +203,10 @@ def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM # no more soft disabling condition, so go back to ENABLED state = State.enabled + elif get_events(events, [ET.SOFT_DISABLE]) and soft_disable_timer > 0: + for e in get_events(events, [ET.SOFT_DISABLE]): + AM.add(e, enabled) + elif soft_disable_timer <= 0: state = State.disabled @@ -210,117 +227,94 @@ def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM return state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last -def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, - awareness_status, PL, LaC, LoC, VM, angle_offset, rear_view_allowed, rear_view_toggle): - # Given the state, this function returns the actuators +def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, + driver_status, PL, LaC, LoC, VM, angle_offset, passive, is_metric, cal_perc): + """Given the state, this function returns an actuators packet""" - # reset actuators to zero actuators = car.CarControl.Actuators.new_message() enabled = isEnabled(state) active = isActive(state) - for b in CS.buttonEvents: - # button presses for rear view - if b.type == "leftBlinker" or b.type == "rightBlinker": - if b.pressed and rear_view_allowed: - rear_view_toggle = True - else: - rear_view_toggle = False - - if b.type == "altButton1" and b.pressed: - rear_view_toggle = not rear_view_toggle + # check if user has interacted with the car + driver_engaged = len(CS.buttonEvents) > 0 or \ + v_cruise_kph != v_cruise_kph_last or \ + CS.steeringPressed + # add eventual driver distracted events + events = driver_status.update(events, driver_engaged, isActive(state), CS.standstill) # send FCW alert if triggered by planner if plan.fcw: AM.add("fcw", enabled) - # ***** state specific actions ***** + # State specific actions - # DISABLED if state in [State.preEnabled, State.disabled]: - LaC.reset() LoC.reset(v_pid=CS.vEgo) - # ENABLED or SOFT_DISABLING elif state in [State.enabled, State.softDisabling]: - - # decrease awareness status - awareness_status -= 0.01/(AWARENESS_TIME) - if awareness_status <= 0.: - AM.add("driverDistracted", enabled) - elif awareness_status <= AWARENESS_PRE_TIME / AWARENESS_TIME and \ - awareness_status >= (AWARENESS_PRE_TIME - 4.) / AWARENESS_TIME: - AM.add("preDriverDistracted", enabled) - # parse warnings from car specific interface for e in get_events(events, [ET.WARNING]): - AM.add(e, enabled) - - # *** angle offset learning *** + extra_text = "" + if e == "belowSteerSpeed": + if is_metric: + extra_text = str(int(round(CP.minSteerSpeed * CV.MS_TO_KPH))) + " kph" + else: + extra_text = str(int(round(CP.minSteerSpeed * CV.MS_TO_MPH))) + " mph" + AM.add(e, enabled, extra_text_2=extra_text) + # Run angle offset learner at 20 Hz if rk.frame % 5 == 2 and plan.lateralValid: - # *** run this at 20hz again *** angle_offset = learn_angle_offset(active, CS.vEgo, angle_offset, PL.PP.c_poly, PL.PP.c_prob, CS.steeringAngle, CS.steeringPressed) - # *** gas/brake PID loop *** + # Gas/Brake PID loop actuators.gas, actuators.brake = LoC.update(active, CS.vEgo, CS.brakePressed, CS.standstill, CS.cruiseState.standstill, v_cruise_kph, plan.vTarget, plan.vTargetFuture, plan.aTarget, CP, PL.lead_1) + # Steering PID loop and lateral MPC + actuators.steer, actuators.steerAngle = LaC.update(active, CS.vEgo, CS.steeringAngle, + CS.steeringPressed, plan.dPoly, angle_offset, CP, VM, PL) - # *** steering PID loop *** - actuators.steer = LaC.update(active, CS.vEgo, CS.steeringAngle, - CS.steeringPressed, plan.dPoly, angle_offset, VM, PL) - - # send a "steering required alert" if saturation count has reached the limit + # Send a "steering required alert" if saturation count has reached the limit if LaC.sat_flag and CP.steerLimitAlert: AM.add("steerSaturated", enabled) - if CP.enableCruise and CS.cruiseState.enabled: - v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH - - # reset conditions for the 6 minutes timout - if CS.buttonEvents or \ - v_cruise_kph != v_cruise_kph_last or \ - CS.steeringPressed or \ - state in [State.preEnabled, State.disabled]: - awareness_status = 1. - - # parse permanent warnings to display constantly + # Parse permanent warnings to display constantly for e in get_events(events, [ET.PERMANENT]): - AM.add(str(e) + "Permanent", enabled) - - # *** process alerts *** + extra_text_1, extra_text_2 = "", "" + if e == "calibrationIncomplete": + extra_text_1 = str(cal_perc) + "%" + if is_metric: + extra_text_2 = str(int(round(Filter.MIN_SPEED * CV.MS_TO_KPH))) + " kph" + else: + extra_text_2 = str(int(round(Filter.MIN_SPEED * CV.MS_TO_MPH))) + " mph" + AM.add(str(e) + "Permanent", enabled, extra_text_1=extra_text_1, extra_text_2=extra_text_2) AM.process_alerts(sec_since_boot()) - return actuators, v_cruise_kph, awareness_status, angle_offset, rear_view_toggle + return actuators, v_cruise_kph, driver_status, angle_offset -def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, - carcontrol, live100, livempc, AM, rear_view_allowed, rear_view_toggle, awareness_status, +def data_send(perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, + carcontrol, live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive): - - # ***** control the car ***** + """Send actuators and hud commands to the car, send live100 and MPC logging""" CC = car.CarControl.new_message() if not passive: - CC.enabled = isEnabled(state) - CC.actuators = actuators CC.cruiseControl.override = True - # always cancel if we have an interceptor CC.cruiseControl.cancel = not CP.enableCruise or (not isEnabled(state) and CS.cruiseState.enabled) - # brake discount removes a sharp nonlinearity - brake_discount = (1.0 - clip(actuators.brake*3., 0.0, 1.0)) + # Some override values for Honda + brake_discount = (1.0 - clip(actuators.brake * 3., 0.0, 1.0)) # brake discount removes a sharp nonlinearity CC.cruiseControl.speedOverride = float(max(0.0, (LoC.v_pid + CS.cruiseState.speedOffset) * brake_discount) if CP.enableCruise else 0.0) CC.cruiseControl.accelOverride = CI.calc_accel_override(CS.aEgo, plan.aTarget, CS.vEgo, plan.vTarget) @@ -332,81 +326,65 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_ CC.hudControl.audibleAlert = AM.audible_alert # send car controls over can - CI.apply(CC) + CI.apply(CC, perception_state) - # ***** publish state to logger ***** - # publish controls state at 100Hz + # live100 dat = messaging.new_message() dat.init('live100') - - # show rear view camera on phone if in reverse gear or when button is pressed - dat.live100.rearViewCam = ('reverseGear' in [e.name for e in events] and rear_view_allowed) or rear_view_toggle - dat.live100.alertText1 = AM.alert_text_1 - dat.live100.alertText2 = AM.alert_text_2 - dat.live100.alertSize = AM.alert_size - dat.live100.alertStatus = AM.alert_status - dat.live100.awarenessStatus = max(awareness_status, 0.0) if isEnabled(state) else 0.0 - - # what packets were used to process - dat.live100.canMonoTimes = list(CS.canMonoTimes) - dat.live100.planMonoTime = plan_ts - - # if controls is enabled - dat.live100.enabled = isEnabled(state) - dat.live100.active = isActive(state) - - # car state - dat.live100.vEgo = CS.vEgo - dat.live100.vEgoRaw = CS.vEgoRaw - dat.live100.angleSteers = CS.steeringAngle - dat.live100.curvature = VM.calc_curvature(CS.steeringAngle * CV.DEG_TO_RAD, CS.vEgo) - dat.live100.steerOverride = CS.steeringPressed - - # high level control state - dat.live100.state = state - - # longitudinal control state - dat.live100.longControlState = LoC.long_control_state - dat.live100.vPid = float(LoC.v_pid) - dat.live100.vCruise = float(v_cruise_kph) - dat.live100.upAccelCmd = float(LoC.pid.p) - dat.live100.uiAccelCmd = float(LoC.pid.i) - dat.live100.ufAccelCmd = float(LoC.pid.f) - - # lateral control state - dat.live100.angleSteersDes = float(LaC.angle_steers_des) - dat.live100.upSteer = float(LaC.pid.p) - dat.live100.uiSteer = float(LaC.pid.i) - dat.live100.ufSteer = float(LaC.pid.f) - - # processed radar state, should add a_pcm? - dat.live100.vTargetLead = float(plan.vTarget) - dat.live100.aTarget = float(plan.aTarget) - dat.live100.jerkFactor = float(plan.jerkFactor) - - # log learned angle offset - dat.live100.angleOffset = float(angle_offset) - - # lag - dat.live100.cumLagMs = -rk.remaining*1000. - + dat.live100 = { + "alertText1": AM.alert_text_1, + "alertText2": AM.alert_text_2, + "alertSize": AM.alert_size, + "alertStatus": AM.alert_status, + "alertBlinkingRate": AM.alert_rate, + "alertType": AM.alert_type, + "alertSound": "", # no EON sounds yet + "awarenessStatus": max(driver_status.awareness, 0.0) if isEnabled(state) else 0.0, + "driverMonitoringOn": bool(driver_status.monitor_on), + "canMonoTimes": list(CS.canMonoTimes), + "planMonoTime": plan_ts, + "enabled": isEnabled(state), + "active": isActive(state), + "vEgo": CS.vEgo, + "vEgoRaw": CS.vEgoRaw, + "angleSteers": CS.steeringAngle, + "curvature": VM.calc_curvature(CS.steeringAngle * CV.DEG_TO_RAD, CS.vEgo), + "steerOverride": CS.steeringPressed, + "state": state, + "engageable": not bool(get_events(events, [ET.NO_ENTRY])), + "longControlState": LoC.long_control_state, + "vPid": float(LoC.v_pid), + "vCruise": float(v_cruise_kph), + "upAccelCmd": float(LoC.pid.p), + "uiAccelCmd": float(LoC.pid.i), + "ufAccelCmd": float(LoC.pid.f), + "angleSteersDes": float(LaC.angle_steers_des), + "upSteer": float(LaC.pid.p), + "uiSteer": float(LaC.pid.i), + "ufSteer": float(LaC.pid.f), + "vTargetLead": float(plan.vTarget), + "aTarget": float(plan.aTarget), + "jerkFactor": float(plan.jerkFactor), + "angleOffset": float(angle_offset), + "gpsPlannerActive": plan.gpsPlannerActive, + "cumLagMs": -rk.remaining * 1000., + } live100.send(dat.to_bytes()) - # broadcast carState + # carState cs_send = messaging.new_message() cs_send.init('carState') - # TODO: override CS.events with all the cumulated events - cs_send.carState = copy(CS) + cs_send.carState = CS + cs_send.carState.events = events carstate.send(cs_send.to_bytes()) - # broadcast carControl + # carControl cc_send = messaging.new_message() cc_send.init('carControl') - cc_send.carControl = copy(CC) + cc_send.carControl = CC carcontrol.send(cc_send.to_bytes()) - #print [i.name for i in events] - # publish mpc state at 20Hz + # send MPC when updated (20 Hz) if hasattr(LaC, 'mpc_updated') and LaC.mpc_updated: dat = messaging.new_message() dat.init('liveMpc') @@ -414,129 +392,136 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_ dat.liveMpc.y = list(LaC.mpc_solution[0].y) dat.liveMpc.psi = list(LaC.mpc_solution[0].psi) dat.liveMpc.delta = list(LaC.mpc_solution[0].delta) + dat.liveMpc.cost = LaC.mpc_solution[0].cost livempc.send(dat.to_bytes()) return CC -def controlsd_thread(gctx, rate=100): +def controlsd_thread(gctx=None, rate=100, default_bias=0.): + gc.disable() + # start the loop set_realtime_priority(3) context = zmq.Context() - params = Params() - # pub + # Pub Sockets live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) livempc = messaging.pub_sock(context, service_list['liveMpc'].port) + is_metric = params.get("IsMetric") == "1" passive = params.get("Passive") != "0" + + # No sendcan if passive if not passive: sendcan = messaging.pub_sock(context, service_list['sendcan'].port) else: sendcan = None - # sub + # Sub sockets poller = zmq.Poller() thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) - + driver_monitor = messaging.sub_sock(context, service_list['driverMonitoring'].port, conflate=True, poller=poller) + gps_location = messaging.sub_sock(context, service_list['gpsLocationExternal'].port, conflate=True, poller=poller) logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() - CI, CP = get_car(logcan, sendcan, 1.0 if passive else None) if CI is None: raise Exception("unsupported car") + # if stock camera is connected, then force passive behavior + if not CP.enableCamera: + passive = True + sendcan = None + if passive: CP.safetyModel = car.CarParams.SafetyModels.noOutput + # Get FCW toggle from settings fcw_enabled = params.get("IsFcwEnabled") == "1" + geofence = None PL = Planner(CP, fcw_enabled) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) - LaC = LatControl(VM) + LaC = LatControl(CP) AM = AlertManager() + driver_status = DriverStatus() if not passive: AM.add("startup", False) - # write CarParams + # Write CarParams for radard and boardd safety mode params.put("CarParams", CP.to_bytes()) state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 + v_cruise_kph_last = 0 overtemp = False free_space = False - cal_status = Calibration.UNCALIBRATED - rear_view_toggle = False - rear_view_allowed = params.get("IsRearViewMirror") == "1" - - # 0.0 - 1.0 - awareness_status = 1. - v_cruise_kph_last = 0 + cal_status = Calibration.INVALID + cal_perc = 0 + mismatch_counter = 0 + low_battery = False - rk = Ratekeeper(rate, print_delay_threshold=2./1000) + rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) - # learned angle offset - angle_offset = 1.5 # Default model bias + # Read angle offset from previous drive, fallback to default + angle_offset = default_bias calibration_params = params.get("CalibrationParams") if calibration_params: try: calibration_params = json.loads(calibration_params) - angle_offset = calibration_params["angle_offset"] + angle_offset = calibration_params["angle_offset2"] except (ValueError, KeyError): pass prof = Profiler(False) # off by default - while 1: + while True: + prof.checkpoint("Ratekeeper", ignore=True) - prof.checkpoint("Ratekeeper", ignore=True) # rk is here - - # sample data and compute car events - CS, events, cal_status, overtemp, free_space = data_sample(CI, CC, thermal, cal, health, poller, cal_status, - overtemp, free_space) + # Sample data and compute car events + CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter = data_sample(CI, CC, thermal, cal, health, + driver_monitor, gps_location, poller, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, geofence, state, mismatch_counter, params) prof.checkpoint("Sample") - # define plan - plan, plan_ts = calc_plan(CS, events, PL, LoC, v_cruise_kph, awareness_status) + # Define longitudinal plan (MPC) + plan, plan_ts = calc_plan(CS, CP, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence) prof.checkpoint("Plan") if not passive: # update control state - state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = state_transition(CS, CP, state, events, soft_disable_timer, - v_cruise_kph, AM) + state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ + state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") - # compute actuators - actuators, v_cruise_kph, awareness_status, angle_offset, rear_view_toggle = state_control(plan, CS, CP, state, events, v_cruise_kph, - v_cruise_kph_last, AM, rk, awareness_status, PL, LaC, LoC, VM, - angle_offset, rear_view_allowed, rear_view_toggle) + # Compute actuators (runs PID loops and lateral MPC) + actuators, v_cruise_kph, driver_status, angle_offset = state_control(plan, CS, CP, state, events, v_cruise_kph, + v_cruise_kph_last, AM, rk, driver_status, PL, LaC, LoC, VM, angle_offset, passive, is_metric, cal_perc) prof.checkpoint("State Control") - # publish data - CC = data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, - rk, carstate, carcontrol, live100, livempc, AM, rear_view_allowed, - rear_view_toggle, awareness_status, LaC, LoC, angle_offset, passive) + # Publish data + CC = data_send(PL.perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, + live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive) prof.checkpoint("Sent") - # *** run loop at fixed rate *** - rk.keep_time() - + rk.keep_time() # Run at 100Hz prof.display() def main(gctx=None): controlsd_thread(gctx, 100) + if __name__ == "__main__": main() diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 82174135e8b274..5884e987033fc3 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -1,478 +1,69 @@ -from cereal import car, log +from cereal import log from selfdrive.swaglog import cloudlog +from selfdrive.controls.lib.alerts import ALERTS from common.realtime import sec_since_boot import copy -# Priority -class Priority: - HIGH = 3 - MID = 2 - LOW = 1 - LOWEST = 0 - AlertSize = log.Live100Data.AlertSize AlertStatus = log.Live100Data.AlertStatus -class Alert(object): - def __init__(self, - alert_text_1, - alert_text_2, - alert_status, - alert_size, - alert_priority, - visual_alert, - audible_alert, - duration_sound, - duration_hud_alert, - duration_text): - - self.alert_text_1 = alert_text_1 - self.alert_text_2 = alert_text_2 - self.alert_status = alert_status - self.alert_size = alert_size - self.alert_priority = alert_priority - self.visual_alert = visual_alert if visual_alert is not None else "none" - self.audible_alert = audible_alert if audible_alert is not None else "none" - - self.duration_sound = duration_sound - self.duration_hud_alert = duration_hud_alert - self.duration_text = duration_text - - self.start_time = 0. - - # typecheck that enums are valid on startup - tst = car.CarControl.new_message() - tst.hudControl.visualAlert = self.visual_alert - tst.hudControl.audibleAlert = self.audible_alert - - def __str__(self): - return self.alert_text_1 + "/" + self.alert_text_2 + " " + str(self.alert_priority) + " " + str( - self.visual_alert) + " " + str(self.audible_alert) - - def __gt__(self, alert2): - return self.alert_priority > alert2.alert_priority - class AlertManager(object): - alerts = { - - # Miscellaneous alerts - "enable": Alert( - "", - "", - AlertStatus.normal, AlertSize.none, - Priority.MID, None, "beepSingle", .2, 0., 0.), - - "disable": Alert( - "", - "", - AlertStatus.normal, AlertSize.none, - Priority.MID, None, "beepSingle", .2, 0., 0.), - - "fcw": Alert( - "Brake!", - "Risk of Collision", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "fcw", "chimeRepeated", 1., 2., 2.), - - "steerSaturated": Alert( - "Take Control", - "Turn Exceeds Limit", - AlertStatus.userPrompt, AlertSize.full, - Priority.LOW, "steerRequired", "chimeSingle", 1., 2., 3.), - - "steerTempUnavailable": Alert( - "Take Control", - "Steer Temporarily Unavailable", - AlertStatus.userPrompt, AlertSize.full, - Priority.LOW, "steerRequired", "chimeDouble", .4, 2., 3.), - - "preDriverDistracted": Alert( - "Take Control", - "User Distracted", - AlertStatus.userPrompt, AlertSize.full, - Priority.LOW, "steerRequired", "chimeDouble", .1, .1, .1), - - "driverDistracted": Alert( - "Take Control to Regain Speed", - "User Distracted", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), - - "startup": Alert( - "Always Keep Hands on Wheel", - "Be Ready to Take Over Any Time", - AlertStatus.normal, AlertSize.full, - Priority.LOWEST, None, None, 0., 0., 15.), - - "ethicalDilemma": Alert( - "Take Control Immediately", - "Ethical Dilemma Detected", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "steerTempUnavailableNoEntry": Alert( - "Comma Unavailable", - "Steer Temporary Unavailable", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "manualRestart": Alert( - "Take Control", - "Resume Driving Manually", - AlertStatus.userPrompt, AlertSize.full, - Priority.LOW, None, None, 0., 0., .2), - - # Non-entry only alerts - "wrongCarModeNoEntry": Alert( - "Comma Unavailable", - "Main Switch Off", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "dataNeededNoEntry": Alert( - "Comma Unavailable", - "Data needed for calibration. Upload drive, try again", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "outOfSpaceNoEntry": Alert( - "Comma Unavailable", - "Out of Space", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "pedalPressedNoEntry": Alert( - "Comma Unavailable", - "Pedal Pressed", - AlertStatus.normal, AlertSize.full, - Priority.LOW, "brakePressed", "chimeDouble", .4, 2., 3.), - - "speedTooLowNoEntry": Alert( - "Comma Unavailable", - "Speed Too Low", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "brakeHoldNoEntry": Alert( - "Comma Unavailable", - "Brake Hold Active", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "parkBrakeNoEntry": Alert( - "Comma Unavailable", - "Park Brake Engaged", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "lowSpeedLockoutNoEntry": Alert( - "Comma Unavailable", - "Cruise Fault: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - # Cancellation alerts causing soft disabling - "overheat": Alert( - "Take Control Immediately", - "System Overheated", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "wrongGear": Alert( - "Take Control Immediately", - "Gear not D", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "calibrationInvalid": Alert( - "Take Control Immediately", - "Calibration Invalid: Reposition EON and Recalibrate", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "calibrationInProgress": Alert( - "Take Control Immediately", - "Calibration in Progress", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "doorOpen": Alert( - "Take Control Immediately", - "Door Open", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "seatbeltNotLatched": Alert( - "Take Control Immediately", - "Seatbelt Unlatched", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "espDisabled": Alert( - "Take Control Immediately", - "ESP Off", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - # Cancellation alerts causing immediate disabling - "radarCommIssue": Alert( - "Take Control Immediately", - "Radar Error: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "radarFault": Alert( - "Take Control Immediately", - "Radar Error: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "modelCommIssue": Alert( - "Take Control Immediately", - "Model Error: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "controlsFailed": Alert( - "Take Control Immediately", - "Controls Failed", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "controlsMismatch": Alert( - "Take Control Immediately", - "Controls Mismatch", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "commIssue": Alert( - "Take Control Immediately", - "CAN Error: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "steerUnavailable": Alert( - "Take Control Immediately", - "Steer Fault: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "brakeUnavailable": Alert( - "Take Control Immediately", - "Brake Fault: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "gasUnavailable": Alert( - "Take Control Immediately", - "Gas Fault: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "reverseGear": Alert( - "Take Control Immediately", - "Reverse Gear", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "cruiseDisabled": Alert( - "Take Control Immediately", - "Cruise Is Off", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.), - - # not loud cancellations (user is in control) - "noTarget": Alert( - "Comma Canceled", - "No Close Lead", - AlertStatus.normal, AlertSize.full, - Priority.HIGH, None, "chimeDouble", .4, 2., 3.), - - "speedTooLow": Alert( - "Comma Canceled", - "Speed Too Low", - AlertStatus.normal, AlertSize.full, - Priority.HIGH, None, "chimeDouble", .4, 2., 3.), - - # Cancellation alerts causing non-entry - "overheatNoEntry": Alert( - "Comma Unavailable", - "System Overheated", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "wrongGearNoEntry": Alert( - "Comma Unavailable", - "Gear not D", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "calibrationInvalidNoEntry": Alert( - "Comma Unavailable", - "Calibration Invalid: Reposition EON and Recalibrate", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "calibrationInProgressNoEntry": Alert( - "Comma Unavailable", - "Calibration in Progress", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "doorOpenNoEntry": Alert( - "Comma Unavailable", - "Door Open", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "seatbeltNotLatchedNoEntry": Alert( - "Comma Unavailable", - "Seatbelt Unlatched", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "espDisabledNoEntry": Alert( - "Comma Unavailable", - "ESP Off", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "radarCommIssueNoEntry": Alert( - "Comma Unavailable", - "Radar Error: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "radarFaultNoEntry": Alert( - "Comma Unavailable", - "Radar Error: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "modelCommIssueNoEntry": Alert( - "Comma Unavailable", - "Model Error: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "controlsFailedNoEntry": Alert( - "Comma Unavailable", - "Controls Failed", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "commIssueNoEntry": Alert( - "Comma Unavailable", - "CAN Error: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "steerUnavailableNoEntry": Alert( - "Comma Unavailable", - "Steer Fault: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "brakeUnavailableNoEntry": Alert( - "Comma Unavailable", - "Brake Fault: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "gasUnavailableNoEntry": Alert( - "Comma Unavailable", - "Gas Error: Restart the Car", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "reverseGearNoEntry": Alert( - "Comma Unavailable", - "Reverse Gear", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "cruiseDisabledNoEntry": Alert( - "Comma Unavailable", - "Cruise is Off", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "noTargetNoEntry": Alert( - "Comma Unavailable", - "No Close Lead", - AlertStatus.normal, AlertSize.full, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - # permanent alerts to display on small UI upper box - "steerUnavailablePermanent": Alert( - "STEER FAULT", - "RESTART THE CAR", - AlertStatus.normal, AlertSize.small, - Priority.LOWEST, None, None, 0., 0., .2), - - "brakeUnavailablePermanent": Alert( - "BRAKE FAULT", - "RESTART THE CAR", - AlertStatus.normal, AlertSize.small, - Priority.LOWEST, None, None, 0., 0., .2), - - "lowSpeedLockoutPermanent": Alert( - "CRUISE FAULT", - "RESTART THE CAR", - AlertStatus.normal, AlertSize.small, - Priority.LOWEST, None, None, 0., 0., .2), - } def __init__(self): self.activealerts = [] + self.alerts = {alert.alert_type: alert for alert in ALERTS} def alertPresent(self): return len(self.activealerts) > 0 - def add(self, alert_type, enabled=True, extra_text=''): + def add(self, alert_type, enabled=True, extra_text_1='', extra_text_2=''): alert_type = str(alert_type) added_alert = copy.copy(self.alerts[alert_type]) - added_alert.alert_text_2 += extra_text + added_alert.alert_text_1 += extra_text_1 + added_alert.alert_text_2 += extra_text_2 added_alert.start_time = sec_since_boot() # if new alert is higher priority, log it - if not self.alertPresent() or \ - added_alert.alert_priority > self.activealerts[0].alert_priority: - cloudlog.event('alert_add', - alert_type=alert_type, - enabled=enabled) + if not self.alertPresent() or added_alert.alert_priority > self.activealerts[0].alert_priority: + cloudlog.event('alert_add', alert_type=alert_type, enabled=enabled) self.activealerts.append(added_alert) - self.activealerts.sort(key=lambda k: k.alert_priority, reverse=True) - # TODO: cycle through alerts? + # sort by priority first and then by start_time + self.activealerts.sort(key=lambda k: (k.alert_priority, k.start_time), reverse=True) + def process_alerts(self, cur_time): # first get rid of all the expired alerts - self.activealerts = [a for a in self.activealerts if a.start_time + + self.activealerts = [a for a in self.activealerts if a.start_time + max(a.duration_sound, a.duration_hud_alert, a.duration_text) > cur_time] - ca = self.activealerts[0] if self.alertPresent() else None + current_alert = self.activealerts[0] if self.alertPresent() else None # start with assuming no alerts + self.alert_type = "" self.alert_text_1 = "" self.alert_text_2 = "" self.alert_status = AlertStatus.normal self.alert_size = AlertSize.none self.visual_alert = "none" self.audible_alert = "none" + self.alert_rate = 0. + + if current_alert: + self.alert_type = current_alert.alert_type - if ca: - if ca.start_time + ca.duration_sound > cur_time: - self.audible_alert = ca.audible_alert + if current_alert.start_time + current_alert.duration_sound > cur_time: + self.audible_alert = current_alert.audible_alert - if ca.start_time + ca.duration_hud_alert > cur_time: - self.visual_alert = ca.visual_alert + if current_alert.start_time + current_alert.duration_hud_alert > cur_time: + self.visual_alert = current_alert.visual_alert - if ca.start_time + ca.duration_text > cur_time: - self.alert_text_1 = ca.alert_text_1 - self.alert_text_2 = ca.alert_text_2 - self.alert_status = ca.alert_status - self.alert_size = ca.alert_size + if current_alert.start_time + current_alert.duration_text > cur_time: + self.alert_text_1 = current_alert.alert_text_1 + self.alert_text_2 = current_alert.alert_text_2 + self.alert_status = current_alert.alert_status + self.alert_size = current_alert.alert_size + self.alert_rate = current_alert.alert_rate diff --git a/selfdrive/controls/lib/alerts.py b/selfdrive/controls/lib/alerts.py new file mode 100644 index 00000000000000..cc9b19d5d4fa70 --- /dev/null +++ b/selfdrive/controls/lib/alerts.py @@ -0,0 +1,627 @@ +from cereal import car, log + +# Priority +class Priority: + LOWEST = 0 + LOW_LOWEST = 1 + LOW = 2 + MID = 3 + HIGH = 4 + HIGHEST = 5 + +AlertSize = log.Live100Data.AlertSize +AlertStatus = log.Live100Data.AlertStatus +AudibleAlert = car.CarControl.HUDControl.AudibleAlert +VisualAlert = car.CarControl.HUDControl.VisualAlert + +class Alert(object): + def __init__(self, + alert_type, + alert_text_1, + alert_text_2, + alert_status, + alert_size, + alert_priority, + visual_alert, + audible_alert, + duration_sound, + duration_hud_alert, + duration_text, + alert_rate=0.): + + self.alert_type = alert_type + self.alert_text_1 = alert_text_1 + self.alert_text_2 = alert_text_2 + self.alert_status = alert_status + self.alert_size = alert_size + self.alert_priority = alert_priority + self.visual_alert = visual_alert + self.audible_alert = audible_alert + + self.duration_sound = duration_sound + self.duration_hud_alert = duration_hud_alert + self.duration_text = duration_text + + self.start_time = 0. + self.alert_rate = alert_rate + + # typecheck that enums are valid on startup + tst = car.CarControl.new_message() + tst.hudControl.visualAlert = self.visual_alert + + def __str__(self): + return self.alert_text_1 + "/" + self.alert_text_2 + " " + str(self.alert_priority) + " " + str( + self.visual_alert) + " " + str(self.audible_alert) + + def __gt__(self, alert2): + return self.alert_priority > alert2.alert_priority + + +ALERTS = [ + # Miscellaneous alerts + Alert( + "enable", + "", + "", + AlertStatus.normal, AlertSize.none, + Priority.MID, VisualAlert.none, AudibleAlert.chimeEngage, .2, 0., 0.), + + Alert( + "disable", + "", + "", + AlertStatus.normal, AlertSize.none, + Priority.MID, VisualAlert.none, AudibleAlert.chimeDisengage, .2, 0., 0.), + + Alert( + "fcw", + "BRAKE!", + "Risk of Collision", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.fcw, AudibleAlert.chimeWarningRepeat, 1., 2., 2.), + + Alert( + "steerSaturated", + "TAKE CONTROL", + "Turn Exceeds Steering Limit", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimePrompt, 1., 2., 3.), + + Alert( + "steerTempUnavailable", + "TAKE CONTROL", + "Steering Temporarily Unavailable", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, .4, 2., 3.), + + Alert( + "steerTempUnavailableMute", + "TAKE CONTROL", + "Steering Temporarily Unavailable", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .2, .2, .2), + + Alert( + "preDriverDistracted", + "KEEP EYES ON ROAD: User Appears Distracted", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), + + Alert( + "promptDriverDistracted", + "KEEP EYES ON ROAD", + "User Appears Distracted", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, .1, .1), + + Alert( + "driverDistracted", + "DISENGAGE IMMEDIATELY", + "User Was Distracted", + AlertStatus.critical, AlertSize.full, + Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), + + Alert( + "preDriverUnresponsive", + "TOUCH STEERING WHEEL: No Driver Monitoring", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), + + Alert( + "promptDriverUnresponsive", + "TOUCH STEERING WHEEL", + "User Is Unresponsive", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, .1, .1), + + Alert( + "driverUnresponsive", + "DISENGAGE IMMEDIATELY", + "User Was Unresponsive", + AlertStatus.critical, AlertSize.full, + Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), + + Alert( + "driverMonitorOff", + "DRIVER MONITOR IS UNAVAILABLE", + "Accuracy Is Low", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .4, 0., 4.), + + Alert( + "driverMonitorOn", + "DRIVER MONITOR IS AVAILABLE", + "Accuracy Is High", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .4, 0., 4.), + + Alert( + "geofence", + "DISENGAGEMENT REQUIRED", + "Not in Geofenced Area", + AlertStatus.userPrompt, AlertSize.mid, + Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), + + Alert( + "startup", + "Be ready to take over at any time", + "Always keep hands on wheel and eyes on road", + AlertStatus.normal, AlertSize.mid, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), + + Alert( + "ethicalDilemma", + "TAKE CONTROL IMMEDIATELY", + "Ethical Dilemma Detected", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 3.), + + Alert( + "steerTempUnavailableNoEntry", + "openpilot Unavailable", + "Steering Temporarily Unavailable", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "manualRestart", + "TAKE CONTROL", + "Resume Driving Manually", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "resumeRequired", + "STOPPED", + "Press Resume to Move", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "belowSteerSpeed", + "TAKE CONTROL", + "Steer Unavailable Below ", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, 0., 0., .1), + + Alert( + "debugAlert", + "DEBUG ALERT", + "", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .1, .1, .1), + + # Non-entry only alerts + Alert( + "wrongCarModeNoEntry", + "openpilot Unavailable", + "Main Switch Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "dataNeededNoEntry", + "openpilot Unavailable", + "Data Needed for Calibration. Upload Drive, Try Again", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "outOfSpaceNoEntry", + "openpilot Unavailable", + "Out of Storage Space", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "pedalPressedNoEntry", + "openpilot Unavailable", + "Pedal Pressed During Attempt", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, "brakePressed", AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "speedTooLowNoEntry", + "openpilot Unavailable", + "Speed Too Low", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "brakeHoldNoEntry", + "openpilot Unavailable", + "Brake Hold Active", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "parkBrakeNoEntry", + "openpilot Unavailable", + "Park Brake Engaged", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "lowSpeedLockoutNoEntry", + "openpilot Unavailable", + "Cruise Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "lowBatteryNoEntry", + "openpilot Unavailable", + "Low Battery", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + # Cancellation alerts causing soft disabling + Alert( + "overheat", + "TAKE CONTROL IMMEDIATELY", + "System Overheated", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "wrongGear", + "TAKE CONTROL IMMEDIATELY", + "Gear not D", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "calibrationInvalid", + "TAKE CONTROL IMMEDIATELY", + "Calibration Invalid: Reposition EON and Recalibrate", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "calibrationIncomplete", + "TAKE CONTROL IMMEDIATELY", + "Calibration in Progress", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "doorOpen", + "TAKE CONTROL IMMEDIATELY", + "Door Open", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "seatbeltNotLatched", + "TAKE CONTROL IMMEDIATELY", + "Seatbelt Unlatched", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "espDisabled", + "TAKE CONTROL IMMEDIATELY", + "ESP Off", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "lowBattery", + "TAKE CONTROL IMMEDIATELY", + "Low Battery", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + # Cancellation alerts causing immediate disabling + Alert( + "radarCommIssue", + "TAKE CONTROL IMMEDIATELY", + "Radar Error: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "radarFault", + "TAKE CONTROL IMMEDIATELY", + "Radar Error: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "modelCommIssue", + "TAKE CONTROL IMMEDIATELY", + "Model Error: Check Internet Connection", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "controlsFailed", + "TAKE CONTROL IMMEDIATELY", + "Controls Failed", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "controlsMismatch", + "TAKE CONTROL IMMEDIATELY", + "Controls Mismatch", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "commIssue", + "TAKE CONTROL IMMEDIATELY", + "CAN Error: Check Connections", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "steerUnavailable", + "TAKE CONTROL IMMEDIATELY", + "LKAS Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "brakeUnavailable", + "TAKE CONTROL IMMEDIATELY", + "Cruise Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "gasUnavailable", + "TAKE CONTROL IMMEDIATELY", + "Gas Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "reverseGear", + "TAKE CONTROL IMMEDIATELY", + "Reverse Gear", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "cruiseDisabled", + "TAKE CONTROL IMMEDIATELY", + "Cruise Is Off", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "plannerError", + "TAKE CONTROL IMMEDIATELY", + "Planner Solution Error", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + # not loud cancellations (user is in control) + Alert( + "noTarget", + "openpilot Canceled", + "No close lead car", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + Alert( + "speedTooLow", + "openpilot Canceled", + "Speed too low", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + Alert( + "invalidGiraffeHonda", + "Invalid Giraffe Configuration", + "Set 0111 for openpilot. 1011 for stock", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + # Cancellation alerts causing non-entry + Alert( + "overheatNoEntry", + "openpilot Unavailable", + "System overheated", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "wrongGearNoEntry", + "openpilot Unavailable", + "Gear not D", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "calibrationInvalidNoEntry", + "openpilot Unavailable", + "Calibration Invalid: Reposition EON and Recalibrate", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "calibrationIncompleteNoEntry", + "openpilot Unavailable", + "Calibration in Progress", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "doorOpenNoEntry", + "openpilot Unavailable", + "Door open", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "seatbeltNotLatchedNoEntry", + "openpilot Unavailable", + "Seatbelt unlatched", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "espDisabledNoEntry", + "openpilot Unavailable", + "ESP Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "geofenceNoEntry", + "openpilot Unavailable", + "Not in Geofenced Area", + AlertStatus.normal, AlertSize.mid, + Priority.MID, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "radarCommIssueNoEntry", + "openpilot Unavailable", + "Radar Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "radarFaultNoEntry", + "openpilot Unavailable", + "Radar Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "modelCommIssueNoEntry", + "openpilot Unavailable", + "Model Error: Check Internet Connection", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "controlsFailedNoEntry", + "openpilot Unavailable", + "Controls Failed", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "commIssueNoEntry", + "openpilot Unavailable", + "CAN Error: Check Connections", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "steerUnavailableNoEntry", + "openpilot Unavailable", + "LKAS Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "brakeUnavailableNoEntry", + "openpilot Unavailable", + "Cruise Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "gasUnavailableNoEntry", + "openpilot Unavailable", + "Gas Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "reverseGearNoEntry", + "openpilot Unavailable", + "Reverse Gear", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "cruiseDisabledNoEntry", + "openpilot Unavailable", + "Cruise is Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "noTargetNoEntry", + "openpilot Unavailable", + "No Close Lead Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "plannerErrorNoEntry", + "openpilot Unavailable", + "Planner Solution Error", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "invalidGiraffeHondaNoEntry", + "openpilot Unavailable", + "Set 0111 for openpilot. 1011 for stock", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + # permanent alerts + Alert( + "steerUnavailablePermanent", + "LKAS Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "brakeUnavailablePermanent", + "Cruise Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "lowSpeedLockoutPermanent", + "Cruise Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "calibrationIncompletePermanent", + "Calibration in Progress: ", + "Drive Above ", + AlertStatus.normal, AlertSize.mid, + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "invalidGiraffeHondaPermanent", + "Invalid Giraffe Configuration", + "Set 0111 for openpilot. 1011 for stock", + AlertStatus.normal, AlertSize.mid, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), +] diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index f98a0233c6831f..9d78c966743569 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,5 +1,26 @@ -from common.numpy_fast import clip from cereal import car +from common.numpy_fast import clip +from selfdrive.config import Conversions as CV + +# kph +V_CRUISE_MAX = 144 +V_CRUISE_MIN = 8 +V_CRUISE_DELTA = 8 +V_CRUISE_ENABLE_MIN = 40 + + +class MPC_COST_LAT: + PATH = 1.0 + LANE = 3.0 + HEADING = 1.0 + STEER_RATE = 1.0 + + +class MPC_COST_LONG: + TTC = 5.0 + DISTANCE = 0.1 + ACCELERATION = 10.0 + JERK = 20.0 class EventTypes: @@ -38,8 +59,8 @@ def learn_angle_offset(lateral_control, v_ego, angle_offset, c_poly, c_prob, ang # simple integral controller that learns how much steering offset to put to have the car going straight # while being in the middle of the lane min_offset = -5. # deg - max_offset = 5. # deg - alpha = 1./36000. # correct by 1 deg in 2 mins, at 30m/s, with 50cm of error, at 20Hz + max_offset = 5. # deg + alpha = 1. / 36000. # correct by 1 deg in 2 mins, at 30m/s, with 50cm of error, at 20Hz min_learn_speed = 1. # learn less at low speed or when turning @@ -52,3 +73,26 @@ def learn_angle_offset(lateral_control, v_ego, angle_offset, c_poly, c_prob, ang angle_offset = clip(angle_offset, min_offset, max_offset) return angle_offset + + +def update_v_cruise(v_cruise_kph, buttonEvents, enabled): + # handle button presses. TODO: this should be in state_control, but a decelCruise press + # would have the effect of both enabling and changing speed is checked after the state transition + for b in buttonEvents: + if enabled and not b.pressed: + if b.type == "accelCruise": + v_cruise_kph += V_CRUISE_DELTA - (v_cruise_kph % V_CRUISE_DELTA) + elif b.type == "decelCruise": + v_cruise_kph -= V_CRUISE_DELTA - ((V_CRUISE_DELTA - v_cruise_kph) % V_CRUISE_DELTA) + v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) + + return v_cruise_kph + + +def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last): + for b in buttonEvents: + # 250kph or above probably means we never had a set speed + if b.type == "accelCruise" and v_cruise_last < 250: + return v_cruise_last + + return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX))) diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/controls/lib/driver_monitor.py new file mode 100644 index 00000000000000..10e0e0be66131b --- /dev/null +++ b/selfdrive/controls/lib/driver_monitor.py @@ -0,0 +1,149 @@ +import numpy as np +from common.realtime import sec_since_boot +from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET +from common.filter_simple import FirstOrderFilter + +_DT = 0.01 # update runs at 100Hz +_DTM = 0.1 # DM runs at 10Hz +_AWARENESS_TIME = 180 # 3 minutes limit without user touching steering wheels make the car enter a terminal status +_AWARENESS_PRE_TIME = 20. # a first alert is issued 20s before expiration +_AWARENESS_PROMPT_TIME = 5. # a second alert is issued 5s before start decelerating the car +_DISTRACTED_TIME = 7. +_DISTRACTED_PRE_TIME = 4. +_DISTRACTED_PROMPT_TIME = 2. +# measured 1 rad in x FOV. 1152x864 is original image, 160x320 is a right crop for model +_CAMERA_FOV_X = 1. # rad +_CAMERA_FOV_Y = 0.75 # 4/3 aspect ratio +# model output refers to center of cropped image, so need to apply the x displacement offset +_CAMERA_OFFSET_X = 0.3125 #(1152/2 - 0.5*(160*864/320))/1152 +_CAMERA_X_CONV = 0.375 # 160*864/320/1152 +_PITCH_WEIGHT = 1.5 # pitch matters a lot more +_METRIC_THRESHOLD = 0.4 +_PITCH_POS_ALLOWANCE = 0.08 # rad, to not be too sensitive on positive pitch +_PITCH_NATURAL_OFFSET = 0.1 # people don't seem to look straight when they drive relaxed, rather a bit up +_STD_THRESHOLD = 0.1 # above this standard deviation consider the measurement invalid +_DISTRACTED_FILTER_TS = 0.25 # 0.6Hz +_VARIANCE_FILTER_TS = 20. # 0.008Hz + + +class _DriverPose(): + def __init__(self): + self.yaw = 0. + self.pitch = 0. + self.roll = 0. + self.yaw_offset = 0. + self.pitch_offset = 0. + +def _monitor_hysteresys(variance_level, monitor_valid_prev): + var_thr = 0.63 if monitor_valid_prev else 0.37 + return variance_level < var_thr + +class DriverStatus(): + def __init__(self, monitor_on=False): + self.pose = _DriverPose() + self.monitor_on = monitor_on + self.monitor_param_on = monitor_on + self.monitor_valid = True # variance needs to be low + self.awareness = 1. + self.driver_distracted = False + self.driver_distraction_filter = FirstOrderFilter(0., _DISTRACTED_FILTER_TS, _DTM) + self.variance_high = False + self.variance_filter = FirstOrderFilter(0., _VARIANCE_FILTER_TS, _DTM) + self.ts_last_check = 0. + self._set_timers() + + def _reset_filters(self): + self.driver_distraction_filter.x = 0. + self.variance_filter.x = 0. + self.monitor_valid = True + + def _set_timers(self): + if self.monitor_on: + self.threshold_pre = _DISTRACTED_PRE_TIME / _DISTRACTED_TIME + self.threshold_prompt = _DISTRACTED_PROMPT_TIME / _DISTRACTED_TIME + self.step_change = _DT / _DISTRACTED_TIME + else: + self.threshold_pre = _AWARENESS_PRE_TIME / _AWARENESS_TIME + self.threshold_prompt = _AWARENESS_PROMPT_TIME / _AWARENESS_TIME + self.step_change = _DT / _AWARENESS_TIME + + def _is_driver_distracted(self, pose): + # to be tuned and to learn the driver's normal pose + yaw_error = pose.yaw - pose.yaw_offset + pitch_error = pose.pitch - pose.pitch_offset - _PITCH_NATURAL_OFFSET + # add positive pitch allowance + if pitch_error > 0.: + pitch_error = max(pitch_error - _PITCH_POS_ALLOWANCE, 0.) + pitch_error *= _PITCH_WEIGHT + metric = np.sqrt(yaw_error**2 + pitch_error**2) + #print "%02.4f" % np.degrees(pose.pitch), "%02.4f" % np.degrees(pitch_error), "%03.4f" % np.degrees(pose.pitch_offset), metric + return 1 if metric > _METRIC_THRESHOLD else 0 + + + def get_pose(self, driver_monitoring, params): + + self.pose.pitch = driver_monitoring.descriptor[0] + self.pose.yaw = driver_monitoring.descriptor[1] + self.pose.roll = driver_monitoring.descriptor[2] + self.pose.yaw_offset = (driver_monitoring.descriptor[3] * _CAMERA_X_CONV + _CAMERA_OFFSET_X) * _CAMERA_FOV_X + self.pose.pitch_offset = -driver_monitoring.descriptor[4] * _CAMERA_FOV_Y # positive y is down + self.driver_distracted = self._is_driver_distracted(self.pose) + # first order filters + self.driver_distraction_filter.update(self.driver_distracted) + self.variance_high = driver_monitoring.std > _STD_THRESHOLD + self.variance_filter.update(self.variance_high) + + monitor_param_on_prev = self.monitor_param_on + monitor_valid_prev = self.monitor_valid + + # don't check for param too often as it's a kernel call + ts = sec_since_boot() + if ts - self.ts_last_check > 1.: + self.monitor_param_on = params.get("IsDriverMonitoringEnabled") == "1" + self.ts_last_check = ts + + self.monitor_valid = _monitor_hysteresys(self.variance_filter.x, monitor_valid_prev) + self.monitor_on = self.monitor_valid and self.monitor_param_on + if monitor_param_on_prev != self.monitor_param_on: + self._reset_filters() + self._set_timers() + + + def update(self, events, driver_engaged, ctrl_active, standstill): + + driver_engaged |= (self.driver_distraction_filter.x < 0.37 and self.monitor_on) + + if (driver_engaged and self.awareness > 0.) or not ctrl_active: + # always reset if driver is in control (unless we are in red alert state) or op isn't active + self.awareness = 1. + + if (not self.monitor_on or (self.driver_distraction_filter.x > 0.63 and self.driver_distracted)) and \ + not (standstill and self.awareness - self.step_change <= self.threshold_prompt): + self.awareness = max(self.awareness - self.step_change, -0.1) + + alert = None + if self.awareness <= 0.: + # terminal red alert: disengagement required + alert = 'driverDistracted' if self.monitor_on else 'driverUnresponsive' + elif self.awareness <= self.threshold_prompt: + # prompt orange alert + alert = 'promptDriverDistracted' if self.monitor_on else 'promptDriverUnresponsive' + elif self.awareness <= self.threshold_pre: + # pre green alert + alert = 'preDriverDistracted' if self.monitor_on else 'preDriverUnresponsive' + if alert is not None: + events.append(create_event(alert, [ET.WARNING])) + + return events + + +if __name__ == "__main__": + ds = DriverStatus(True) + ds.driver_distraction_filter.x = 0. + ds.driver_distracted = 1 + for i in range(10): + ds.update([], False, True, False) + print(ds.awareness, ds.driver_distracted, ds.driver_distraction_filter.x) + ds.update([], True, True, False) + print(ds.awareness, ds.driver_distracted, ds.driver_distraction_filter.x) + diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index 1feec0f5647a0a..81a371f783ca6c 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -1,22 +1,20 @@ import math import numpy as np - from selfdrive.controls.lib.pid import PIController +from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT from selfdrive.controls.lib.lateral_mpc import libmpc_py from common.numpy_fast import interp from common.realtime import sec_since_boot from selfdrive.swaglog import cloudlog - -# 100ms is a rule of thumb estimation of lag from image processing to actuator command -ACTUATORS_DELAY = 0.1 +from cereal import car _DT = 0.01 # 100Hz _DT_MPC = 0.05 # 20Hz -def calc_states_after_delay(states, v_ego, steer_angle, curvature_factor, steer_ratio): - states[0].x = v_ego * ACTUATORS_DELAY - states[0].psi = v_ego * curvature_factor * math.radians(steer_angle) / steer_ratio * ACTUATORS_DELAY +def calc_states_after_delay(states, v_ego, steer_angle, curvature_factor, steer_ratio, delay): + states[0].x = v_ego * delay + states[0].psi = v_ego * curvature_factor * math.radians(steer_angle) / steer_ratio * delay return states @@ -25,18 +23,21 @@ def get_steer_max(CP, v_ego): class LatControl(object): - def __init__(self, VM): - self.pid = PIController(VM.CP.steerKp, VM.CP.steerKi, k_f=VM.CP.steerKf, pos_limit=1.0) + def __init__(self, CP): + self.pid = PIController((CP.steerKpBP, CP.steerKpV), + (CP.steerKiBP, CP.steerKiV), + k_f=CP.steerKf, pos_limit=1.0) self.last_cloudlog_t = 0.0 - self.setup_mpc(VM.CP.steerRateCost) + self.setup_mpc(CP.steerRateCost) def setup_mpc(self, steer_rate_cost): self.libmpc = libmpc_py.libmpc - self.libmpc.init(steer_rate_cost) + self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, steer_rate_cost) self.mpc_solution = libmpc_py.ffi.new("log_t *") self.cur_state = libmpc_py.ffi.new("state_t *") self.mpc_updated = False + self.mpc_nans = False self.cur_state[0].x = 0.0 self.cur_state[0].y = 0.0 self.cur_state[0].psi = 0.0 @@ -51,9 +52,10 @@ def setup_mpc(self, steer_rate_cost): def reset(self): self.pid.reset() - def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offset, VM, PL): + def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offset, CP, VM, PL): cur_time = sec_since_boot() self.mpc_updated = False + # TODO: this creates issues in replay when rewinding time: mpc won't run if self.last_mpc_ts < PL.last_md_ts: self.last_mpc_ts = PL.last_md_ts self.angle_steers_des_prev = self.angle_steers_des_mpc @@ -65,26 +67,31 @@ def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offs p_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.p_poly)) # account for actuation delay - self.cur_state = calc_states_after_delay(self.cur_state, v_ego, angle_steers, curvature_factor, VM.CP.steerRatio) + self.cur_state = calc_states_after_delay(self.cur_state, v_ego, angle_steers, curvature_factor, CP.steerRatio, CP.steerActuatorDelay) v_ego_mpc = max(v_ego, 5.0) # avoid mpc roughness due to low speed self.libmpc.run_mpc(self.cur_state, self.mpc_solution, l_poly, r_poly, p_poly, PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, curvature_factor, v_ego_mpc, PL.PP.lane_width) - delta_desired = self.mpc_solution[0].delta[1] + # reset to current steer angle if not active or overriding + if active: + delta_desired = self.mpc_solution[0].delta[1] + else: + delta_desired = math.radians(angle_steers - angle_offset) / CP.steerRatio + self.cur_state[0].delta = delta_desired - self.angle_steers_des_mpc = float(math.degrees(delta_desired * VM.CP.steerRatio) + angle_offset) + self.angle_steers_des_mpc = float(math.degrees(delta_desired * CP.steerRatio) + angle_offset) self.angle_steers_des_time = cur_time self.mpc_updated = True # Check for infeasable MPC solution - nans = np.any(np.isnan(list(self.mpc_solution[0].delta))) + self.mpc_nans = np.any(np.isnan(list(self.mpc_solution[0].delta))) t = sec_since_boot() - if nans: - self.libmpc.init(VM.CP.steerRateCost) - self.cur_state[0].delta = math.radians(angle_steers) / VM.CP.steerRatio + if self.mpc_nans: + self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, CP.steerRateCost) + self.cur_state[0].delta = math.radians(angle_steers) / CP.steerRatio if t > self.last_cloudlog_t + 5.0: self.last_cloudlog_t = t @@ -94,16 +101,20 @@ def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offs output_steer = 0.0 self.pid.reset() else: - dt = min(cur_time - self.angle_steers_des_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps # TODO: ideally we should interp, but for tuning reasons we keep the mpc solution # constant for 0.05s. + #dt = min(cur_time - self.angle_steers_des_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps #self.angle_steers_des = self.angle_steers_des_prev + (dt / _DT_MPC) * (self.angle_steers_des_mpc - self.angle_steers_des_prev) self.angle_steers_des = self.angle_steers_des_mpc - steers_max = get_steer_max(VM.CP, v_ego) + steers_max = get_steer_max(CP, v_ego) self.pid.pos_limit = steers_max self.pid.neg_limit = -steers_max - steer_feedforward = self.angle_steers_des * v_ego**2 # proportional to realigning tire momentum (~ lateral accel) - output_steer = self.pid.update(self.angle_steers_des, angle_steers, check_saturation=(v_ego > 10), override=steer_override, feedforward=steer_feedforward) + steer_feedforward = self.angle_steers_des # feedforward desired angle + if CP.steerControlType == car.CarParams.SteerControlType.torque: + steer_feedforward *= v_ego**2 # proportional to realigning tire momentum (~ lateral accel) + deadzone = 0.0 + output_steer = self.pid.update(self.angle_steers_des, angle_steers, check_saturation=(v_ego > 10), override=steer_override, + feedforward=steer_feedforward, speed=v_ego, deadzone=deadzone) self.sat_flag = self.pid.saturated - return output_steer + return output_steer, float(self.angle_steers_des) diff --git a/selfdrive/controls/lib/lateral_mpc/Makefile b/selfdrive/controls/lib/lateral_mpc/Makefile index becef563e5ea53..97579e751c833e 100644 --- a/selfdrive/controls/lib/lateral_mpc/Makefile +++ b/selfdrive/controls/lib/lateral_mpc/Makefile @@ -4,6 +4,7 @@ CXX = clang++ PHONELIBS = ../../../../phonelibs +UNAME_S := $(shell uname -s) UNAME_M := $(shell uname -m) CFLAGS = -O3 -fPIC -I. @@ -13,70 +14,63 @@ QPOASES_FLAGS = -I$(PHONELIBS)/qpoases -I$(PHONELIBS)/qpoases/INCLUDE -I$(PHONEL ACADO_FLAGS = -I$(PHONELIBS)/acado/include -I$(PHONELIBS)/acado/include/acado -ifeq ($(UNAME_M),aarch64) -ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +ifeq ($(UNAME_S),Darwin) + ACADO_LIBS := -lacado_toolkit_s +else ifeq ($(UNAME_M),aarch64) + ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a else -ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a + ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a endif OBJS = \ - qp/Bounds.o \ - qp/Constraints.o \ - qp/CyclingManager.o \ - qp/Indexlist.o \ - qp/MessageHandling.o \ - qp/QProblem.o \ - qp/QProblemB.o \ - qp/SubjectTo.o \ - qp/Utils.o \ - qp/EXTRAS/SolutionAnalysis.o \ - mpc_export/acado_qpoases_interface.o \ - mpc_export/acado_integrator.o \ - mpc_export/acado_solver.o \ - mpc_export/acado_auxiliary_functions.o \ - mpc.o + lib_qp/Bounds.o \ + lib_qp/Constraints.o \ + lib_qp/CyclingManager.o \ + lib_qp/Indexlist.o \ + lib_qp/MessageHandling.o \ + lib_qp/QProblem.o \ + lib_qp/QProblemB.o \ + lib_qp/SubjectTo.o \ + lib_qp/Utils.o \ + lib_qp/EXTRAS/SolutionAnalysis.o \ + lib_mpc_export/acado_qpoases_interface.o \ + lib_mpc_export/acado_integrator.o \ + lib_mpc_export/acado_solver.o \ + lib_mpc_export/acado_auxiliary_functions.o \ + lateral_mpc.o DEPS := $(OBJS:.o=.d) .PHONY: all -all: libcommampc.so +all: libmpc.so -libcommampc.so: $(OBJS) +libmpc.so: $(OBJS) $(CXX) -shared -o '$@' $^ -lm - -qp/%.o: $(PHONELIBS)/qpoases/SRC/%.cpp - @echo "[ CXX ] $@" - mkdir -p qp - $(CXX) $(CXXFLAGS) -MMD \ - -I mpc_export/ \ - $(QPOASES_FLAGS) \ - -c -o '$@' '$<' - -qp/EXTRAS/%.o: $(PHONELIBS)/qpoases/SRC/EXTRAS/%.cpp +lib_qp/%.o: $(PHONELIBS)/qpoases/SRC/%.cpp @echo "[ CXX ] $@" - mkdir -p qp/EXTRAS + mkdir -p lib_qp/EXTRAS $(CXX) $(CXXFLAGS) -MMD \ - -I mpc_export/ \ + -I lib_mpc_export/ \ $(QPOASES_FLAGS) \ -c -o '$@' '$<' %.o: %.cpp @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) -MMD \ - -I mpc_export/ \ + -I lib_mpc_export/ \ $(QPOASES_FLAGS) \ -c -o '$@' '$<' %.o: %.c @echo "[ CC ] $@" $(CC) $(CFLAGS) -MMD \ - -I mpc_export/ \ + -I lib_mpc_export/ \ $(QPOASES_FLAGS) \ -c -o '$@' '$<' generator: generator.cpp - $(CXX) -Wall -std=c++11 \ + $(CXX) -v -Wall -std=c++11 \ generator.cpp \ -o generator \ $(ACADO_FLAGS) \ @@ -88,6 +82,6 @@ generate: generator .PHONY: clean clean: - rm -f libcommampc.so generator $(OBJS) $(DEPS) + rm -f *.so generator $(OBJS) $(DEPS) -include $(DEPS) diff --git a/selfdrive/controls/lib/lateral_mpc/generator.cpp b/selfdrive/controls/lib/lateral_mpc/generator.cpp index 53438a11f8f5f3..9af88f9dc8a732 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*PI) const int controlHorizon = 50; -const double samplingTime = 0.05; // 20 Hz using namespace std; @@ -46,25 +45,29 @@ int main( ) auto angle_r = atan(3*r_poly_r0*xx*xx + 2*r_poly_r1*xx + r_poly_r2); auto angle_p = atan(3*p_poly_r0*xx*xx + 2*p_poly_r1*xx + p_poly_r2); - auto c_left_lane = exp(-(poly_l - yy)); - auto c_right_lane = exp(poly_r - yy); + // given the lane width estimate, this is where we estimate the path given lane lines + auto l_phantom = poly_l - lane_width/2.0; + auto r_phantom = poly_r + lane_width/2.0; - auto r_phantom = poly_l - lane_width/2.0; - auto l_phantom = poly_r + lane_width/2.0; - - auto path = lr_prob * (l_prob * r_phantom + r_prob * l_phantom) / (l_prob + r_prob + 0.0001) + // best path estimate path is a linear combination of poly_p and the path estimate + // given the lane lines + auto path = lr_prob * (l_prob * l_phantom + r_prob * r_phantom) / (l_prob + r_prob + 0.0001) + (1-lr_prob) * poly_p; auto angle = lr_prob * (l_prob * angle_l + r_prob * angle_r) / (l_prob + r_prob + 0.0001) + (1-lr_prob) * angle_p; + // instead of using actual lane lines, use their estimated distance from path given lane_width + auto c_left_lane = exp(-(path + lane_width/2.0 - yy)); + auto c_right_lane = exp(path - lane_width/2.0 - yy); + // Running cost Function h; // Distance errors h << path - yy; - h << l_prob * c_left_lane; - h << r_prob * c_right_lane; + h << lr_prob * c_left_lane; + h << lr_prob * c_right_lane; // Heading error h << (v_ref + 1.0 ) * (angle - psi); @@ -116,9 +119,10 @@ int main( ) ocp.minimizeLSQ(Q, h); ocp.minimizeLSQEndTerm(QN, hN); + // car can't go backward to avoid "circles" ocp.subjectTo( deg2rad(-90) <= psi <= deg2rad(90)); - ocp.subjectTo( deg2rad(-25) <= delta <= deg2rad(25)); - ocp.subjectTo( -0.1 <= t <= 0.1); + // more than absolute max steer angle + ocp.subjectTo( deg2rad(-50) <= delta <= deg2rad(50)); ocp.setNOD(18); OCPexport mpc(ocp); @@ -137,7 +141,7 @@ int main( ) mpc.set( GENERATE_MATLAB_INTERFACE, NO ); mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); - if (mpc.exportCode( "mpc_export" ) != SUCCESSFUL_RETURN) + if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) exit( EXIT_FAILURE ); mpc.printDimensionsQP( ); diff --git a/selfdrive/controls/lib/lateral_mpc/mpc.c b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.c similarity index 67% rename from selfdrive/controls/lib/lateral_mpc/mpc.c rename to selfdrive/controls/lib/lateral_mpc/lateral_mpc.c index 3c082319eec6ba..f4cee7f2d0a2aa 100644 --- a/selfdrive/controls/lib/lateral_mpc/mpc.c +++ b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.c @@ -22,15 +22,17 @@ typedef struct { typedef struct { - double x[N]; - double y[N]; - double psi[N]; - double delta[N]; + double x[N+1]; + double y[N+1]; + double psi[N+1]; + double delta[N+1]; + double cost; } log_t; -void init(double steerRateCost){ +void init(double pathCost, double laneCost, double headingCost, double steerRateCost){ acado_initializeSolver(); int i; + const int STEP_MULTIPLIER = 3; /* Initialize the states and controls. */ for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0; @@ -46,18 +48,18 @@ void init(double steerRateCost){ for (i = 0; i < N; i++) { int f = 1; if (i > 4){ - f = 3; + f = STEP_MULTIPLIER; } - acadoVariables.W[25 * i + 0] = 1.0 * f; - acadoVariables.W[25 * i + 6] = 1.0 * f; - acadoVariables.W[25 * i + 12] = 1.0 * f; - acadoVariables.W[25 * i + 18] = 1.0 * f; + acadoVariables.W[25 * i + 0] = pathCost * f; + acadoVariables.W[25 * i + 6] = laneCost * f; + acadoVariables.W[25 * i + 12] = laneCost * f; + acadoVariables.W[25 * i + 18] = headingCost * f; acadoVariables.W[25 * i + 24] = steerRateCost * f; } - acadoVariables.WN[0] = 1.0; - acadoVariables.WN[5] = 1.0; - acadoVariables.WN[10] = 1.0; - acadoVariables.WN[15] = 1.0; + acadoVariables.WN[0] = pathCost * STEP_MULTIPLIER; + acadoVariables.WN[5] = laneCost * STEP_MULTIPLIER; + acadoVariables.WN[10] = laneCost * STEP_MULTIPLIER; + acadoVariables.WN[15] = headingCost * STEP_MULTIPLIER; } int run_mpc(state_t * x0, log_t * solution, @@ -101,18 +103,22 @@ int run_mpc(state_t * x0, log_t * solution, acado_preparationStep(); acado_feedbackStep(); - /* printf("lat its: %d\n", acado_getNWSR()); */ - - for (i = 0; i <= N; i++){ - solution->x[i] = acadoVariables.x[i*NX]; - solution->y[i] = acadoVariables.x[i*NX+1]; - solution->psi[i] = acadoVariables.x[i*NX+2]; - solution->delta[i] = acadoVariables.x[i*NX+3]; - } - - acado_shiftStates(2, 0, 0); - acado_shiftControls( 0 ); + + /* printf("lat its: %d\n", acado_getNWSR()); // n iterations + printf("Objective: %.6f\n", acado_getObjective()); // solution cost */ + + for (i = 0; i <= N; i++){ + solution->x[i] = acadoVariables.x[i*NX]; + solution->y[i] = acadoVariables.x[i*NX+1]; + solution->psi[i] = acadoVariables.x[i*NX+2]; + solution->delta[i] = acadoVariables.x[i*NX+3]; + } + solution->cost = acado_getObjective(); + // Dont shift states here. Current solution is closer to next timestep than if + // we use the old solution as a starting point + //acado_shiftStates(2, 0, 0); + //acado_shiftControls( 0 ); return acado_getNWSR(); } diff --git a/selfdrive/controls/lib/lateral_mpc/lateral_mpc.d b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.d new file mode 100644 index 00000000000000..6cac7c2e148128 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.d @@ -0,0 +1,3 @@ +lateral_mpc.o: lateral_mpc.c lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/lateral_mpc/lateral_mpc.o b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.o new file mode 100644 index 00000000000000..029fda217c0111 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.c similarity index 100% rename from selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.c rename to selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.c diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.d new file mode 100644 index 00000000000000..50c6a60d1fb846 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.d @@ -0,0 +1,5 @@ +lib_mpc_export/acado_auxiliary_functions.o: \ + lib_mpc_export/acado_auxiliary_functions.c \ + lib_mpc_export/acado_auxiliary_functions.h \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.h b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.h similarity index 100% rename from selfdrive/controls/lib/lateral_mpc/mpc_export/acado_auxiliary_functions.h rename to selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.o new file mode 100644 index 00000000000000..07d92429b217f2 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_common.h b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h similarity index 99% rename from selfdrive/controls/lib/lateral_mpc/mpc_export/acado_common.h rename to selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h index dbb20c566dab6c..d5b56727707ff0 100644 --- a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_common.h +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h @@ -184,8 +184,8 @@ real_t evGx[ 320 ]; /** Column vector of size: 80 */ real_t evGu[ 80 ]; -/** Column vector of size: 19 */ -real_t objAuxVar[ 19 ]; +/** Column vector of size: 21 */ +real_t objAuxVar[ 21 ]; /** Row vector of size: 23 */ real_t objValueIn[ 23 ]; diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_integrator.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c similarity index 100% rename from selfdrive/controls/lib/lateral_mpc/mpc_export/acado_integrator.c rename to selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.d new file mode 100644 index 00000000000000..7c057e5ec0f3a9 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_integrator.o: lib_mpc_export/acado_integrator.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.o new file mode 100644 index 00000000000000..d08f1e41279bb7 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.cpp b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.cpp similarity index 100% rename from selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.cpp rename to selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.cpp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.d new file mode 100644 index 00000000000000..ba3c6ef1c831b7 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.d @@ -0,0 +1,24 @@ +lib_mpc_export/acado_qpoases_interface.o: \ + lib_mpc_export/acado_qpoases_interface.cpp \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp similarity index 100% rename from selfdrive/controls/lib/lateral_mpc/mpc_export/acado_qpoases_interface.hpp rename to selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.o new file mode 100644 index 00000000000000..e10c9772ab2b29 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c similarity index 96% rename from selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c rename to selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c index ed897e3c02ae4c..85b67db8a12249 100644 --- a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c @@ -99,49 +99,51 @@ 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; -/* Vector of auxiliary variables; number of elements: 19. */ +/* Vector of auxiliary variables; number of elements: 21. */ real_t* a = acadoWorkspace.objAuxVar; /* Compute intermediate quantities: */ -a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); -a[1] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); +a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[1] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); a[2] = (atan(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]))); a[3] = (atan(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]))); a[4] = (atan(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]))); a[5] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); -a[6] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); -a[7] = (((real_t)(0.0000000000000000e+00)-(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))*a[6]); -a[8] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[6]); -a[9] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); -a[10] = ((((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8])*a[9]); -a[11] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[9]); -a[12] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); -a[13] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[12]); -a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); -a[15] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[14]); -a[16] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); -a[17] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); -a[18] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[17]); +a[6] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[7] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[8] = (((real_t)(0.0000000000000000e+00)-(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[6])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))))*a[7]); +a[9] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[7]); +a[10] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[11] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); +a[12] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[10])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12])))*a[11]); +a[13] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[11]); +a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); +a[15] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[14]); +a[16] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); +a[17] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[16]); +a[18] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[19] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); +a[20] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[19]); /* Compute outputs: */ out[0] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-xd[1]); -out[1] = (od[14]*a[0]); -out[2] = (od[15]*a[1]); +out[1] = (((od[14]+od[15])-(od[14]*od[15]))*a[0]); +out[2] = (((od[14]+od[15])-(od[14]*od[15]))*a[1]); out[3] = ((od[1]+(real_t)(1.0000000000000000e+00))*((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[2])+(od[15]*a[3])))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[4]))-xd[2])); out[4] = ((od[1]+(real_t)(1.0000000000000000e+00))*u[0]); out[5] = (((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[5])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))); out[6] = ((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)); out[7] = (real_t)(0.0000000000000000e+00); out[8] = (real_t)(0.0000000000000000e+00); -out[9] = (od[14]*a[7]); -out[10] = (od[14]*a[8]); +out[9] = (((od[14]+od[15])-(od[14]*od[15]))*a[8]); +out[10] = (((od[14]+od[15])-(od[14]*od[15]))*a[9]); out[11] = (real_t)(0.0000000000000000e+00); out[12] = (real_t)(0.0000000000000000e+00); -out[13] = (od[15]*a[10]); -out[14] = (od[15]*a[11]); +out[13] = (((od[14]+od[15])-(od[14]*od[15]))*a[12]); +out[14] = (((od[14]+od[15])-(od[14]*od[15]))*a[13]); out[15] = (real_t)(0.0000000000000000e+00); out[16] = (real_t)(0.0000000000000000e+00); -out[17] = ((od[1]+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[13])+(od[15]*a[15])))*a[16])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[18]))); +out[17] = ((od[1]+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[15])+(od[15]*a[17])))*a[18])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[20]))); out[18] = (real_t)(0.0000000000000000e+00); out[19] = ((od[1]+(real_t)(1.0000000000000000e+00))*((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))); out[20] = (real_t)(0.0000000000000000e+00); @@ -160,29 +162,31 @@ void acado_evaluateLSQEndTerm(const real_t* in, real_t* out) { const real_t* xd = in; const real_t* od = in + 4; -/* Vector of auxiliary variables; number of elements: 19. */ +/* Vector of auxiliary variables; number of elements: 21. */ real_t* a = acadoWorkspace.objAuxVar; /* Compute intermediate quantities: */ -a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); -a[1] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); +a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[1] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); a[2] = (atan(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]))); a[3] = (atan(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]))); a[4] = (atan(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]))); a[5] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); -a[6] = (exp(((real_t)(0.0000000000000000e+00)-(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-xd[1])))); -a[7] = (((real_t)(0.0000000000000000e+00)-(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))*a[6]); -a[8] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[6]); -a[9] = (exp((((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])-xd[1]))); -a[10] = ((((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8])*a[9]); -a[11] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[9]); -a[12] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); -a[13] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[12]); -a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); -a[15] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[14]); -a[16] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); -a[17] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); -a[18] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[17]); +a[6] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[7] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[8] = (((real_t)(0.0000000000000000e+00)-(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[6])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))))*a[7]); +a[9] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[7]); +a[10] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[11] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); +a[12] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[10])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12])))*a[11]); +a[13] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[11]); +a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); +a[15] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[14]); +a[16] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); +a[17] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[16]); +a[18] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[19] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); +a[20] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[19]); /* Compute outputs: */ out[0] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-xd[1]); @@ -193,15 +197,15 @@ out[4] = (((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])* out[5] = ((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)); out[6] = (real_t)(0.0000000000000000e+00); out[7] = (real_t)(0.0000000000000000e+00); -out[8] = (od[14]*a[7]); -out[9] = (od[14]*a[8]); +out[8] = (od[14]*a[8]); +out[9] = (od[14]*a[9]); out[10] = (real_t)(0.0000000000000000e+00); out[11] = (real_t)(0.0000000000000000e+00); -out[12] = (od[15]*a[10]); -out[13] = (od[15]*a[11]); +out[12] = (od[15]*a[12]); +out[13] = (od[15]*a[13]); out[14] = (real_t)(0.0000000000000000e+00); out[15] = (real_t)(0.0000000000000000e+00); -out[16] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[13])+(od[15]*a[15])))*a[16])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[18]))); +out[16] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[15])+(od[15]*a[17])))*a[18])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[20]))); out[17] = (real_t)(0.0000000000000000e+00); out[18] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))); out[19] = (real_t)(0.0000000000000000e+00); @@ -3948,46 +3952,46 @@ 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.0000000000000001e-01 - acadoVariables.u[0]; -acadoWorkspace.lb[5] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[1]; -acadoWorkspace.lb[6] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[2]; -acadoWorkspace.lb[7] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[3]; -acadoWorkspace.lb[8] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[4]; -acadoWorkspace.lb[9] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[5]; -acadoWorkspace.lb[10] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[6]; -acadoWorkspace.lb[11] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[7]; -acadoWorkspace.lb[12] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[8]; -acadoWorkspace.lb[13] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[9]; -acadoWorkspace.lb[14] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[10]; -acadoWorkspace.lb[15] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[11]; -acadoWorkspace.lb[16] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[12]; -acadoWorkspace.lb[17] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[13]; -acadoWorkspace.lb[18] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[14]; -acadoWorkspace.lb[19] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[15]; -acadoWorkspace.lb[20] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[16]; -acadoWorkspace.lb[21] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[17]; -acadoWorkspace.lb[22] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[18]; -acadoWorkspace.lb[23] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[19]; -acadoWorkspace.ub[4] = (real_t)1.0000000000000001e-01 - acadoVariables.u[0]; -acadoWorkspace.ub[5] = (real_t)1.0000000000000001e-01 - acadoVariables.u[1]; -acadoWorkspace.ub[6] = (real_t)1.0000000000000001e-01 - acadoVariables.u[2]; -acadoWorkspace.ub[7] = (real_t)1.0000000000000001e-01 - acadoVariables.u[3]; -acadoWorkspace.ub[8] = (real_t)1.0000000000000001e-01 - acadoVariables.u[4]; -acadoWorkspace.ub[9] = (real_t)1.0000000000000001e-01 - acadoVariables.u[5]; -acadoWorkspace.ub[10] = (real_t)1.0000000000000001e-01 - acadoVariables.u[6]; -acadoWorkspace.ub[11] = (real_t)1.0000000000000001e-01 - acadoVariables.u[7]; -acadoWorkspace.ub[12] = (real_t)1.0000000000000001e-01 - acadoVariables.u[8]; -acadoWorkspace.ub[13] = (real_t)1.0000000000000001e-01 - acadoVariables.u[9]; -acadoWorkspace.ub[14] = (real_t)1.0000000000000001e-01 - acadoVariables.u[10]; -acadoWorkspace.ub[15] = (real_t)1.0000000000000001e-01 - acadoVariables.u[11]; -acadoWorkspace.ub[16] = (real_t)1.0000000000000001e-01 - acadoVariables.u[12]; -acadoWorkspace.ub[17] = (real_t)1.0000000000000001e-01 - acadoVariables.u[13]; -acadoWorkspace.ub[18] = (real_t)1.0000000000000001e-01 - acadoVariables.u[14]; -acadoWorkspace.ub[19] = (real_t)1.0000000000000001e-01 - acadoVariables.u[15]; -acadoWorkspace.ub[20] = (real_t)1.0000000000000001e-01 - acadoVariables.u[16]; -acadoWorkspace.ub[21] = (real_t)1.0000000000000001e-01 - acadoVariables.u[17]; -acadoWorkspace.ub[22] = (real_t)1.0000000000000001e-01 - acadoVariables.u[18]; -acadoWorkspace.ub[23] = (real_t)1.0000000000000001e-01 - acadoVariables.u[19]; +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]; for (lRun1 = 0; lRun1 < 40; ++lRun1) { @@ -4477,122 +4481,122 @@ 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; tmp = acadoVariables.x[7] + acadoWorkspace.d[3]; -acadoWorkspace.lbA[1] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[1] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[1] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[1] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[11] + acadoWorkspace.d[7]; -acadoWorkspace.lbA[3] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[3] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[3] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[3] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[15] + acadoWorkspace.d[11]; -acadoWorkspace.lbA[5] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[5] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[5] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[5] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[19] + acadoWorkspace.d[15]; -acadoWorkspace.lbA[7] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[7] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[7] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[7] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[23] + acadoWorkspace.d[19]; -acadoWorkspace.lbA[9] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[9] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[9] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[9] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[27] + acadoWorkspace.d[23]; -acadoWorkspace.lbA[11] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[11] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[11] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[11] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[31] + acadoWorkspace.d[27]; -acadoWorkspace.lbA[13] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[13] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[13] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[13] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[35] + acadoWorkspace.d[31]; -acadoWorkspace.lbA[15] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[15] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[15] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[15] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[39] + acadoWorkspace.d[35]; -acadoWorkspace.lbA[17] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[17] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[17] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[17] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[43] + acadoWorkspace.d[39]; -acadoWorkspace.lbA[19] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[19] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[19] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[19] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[47] + acadoWorkspace.d[43]; -acadoWorkspace.lbA[21] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[21] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[21] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[21] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[51] + acadoWorkspace.d[47]; -acadoWorkspace.lbA[23] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[23] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[23] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[23] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[55] + acadoWorkspace.d[51]; -acadoWorkspace.lbA[25] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[25] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[25] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[25] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[59] + acadoWorkspace.d[55]; -acadoWorkspace.lbA[27] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[27] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[27] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[27] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[63] + acadoWorkspace.d[59]; -acadoWorkspace.lbA[29] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[29] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[29] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[29] = (real_t)8.7266462600000005e-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; tmp = acadoVariables.x[67] + acadoWorkspace.d[63]; -acadoWorkspace.lbA[31] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[31] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[31] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[31] = (real_t)8.7266462600000005e-01 - tmp; tmp = acadoVariables.x[70] + acadoWorkspace.d[66]; acadoWorkspace.lbA[32] = (real_t)-1.5707963268000000e+00 - tmp; acadoWorkspace.ubA[32] = (real_t)1.5707963268000000e+00 - tmp; tmp = acadoVariables.x[71] + acadoWorkspace.d[67]; -acadoWorkspace.lbA[33] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[33] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[33] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[33] = (real_t)8.7266462600000005e-01 - tmp; tmp = acadoVariables.x[74] + acadoWorkspace.d[70]; acadoWorkspace.lbA[34] = (real_t)-1.5707963268000000e+00 - tmp; acadoWorkspace.ubA[34] = (real_t)1.5707963268000000e+00 - tmp; tmp = acadoVariables.x[75] + acadoWorkspace.d[71]; -acadoWorkspace.lbA[35] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[35] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[35] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[35] = (real_t)8.7266462600000005e-01 - tmp; tmp = acadoVariables.x[78] + acadoWorkspace.d[74]; acadoWorkspace.lbA[36] = (real_t)-1.5707963268000000e+00 - tmp; acadoWorkspace.ubA[36] = (real_t)1.5707963268000000e+00 - tmp; tmp = acadoVariables.x[79] + acadoWorkspace.d[75]; -acadoWorkspace.lbA[37] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[37] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[37] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[37] = (real_t)8.7266462600000005e-01 - tmp; tmp = acadoVariables.x[82] + acadoWorkspace.d[78]; acadoWorkspace.lbA[38] = (real_t)-1.5707963268000000e+00 - tmp; acadoWorkspace.ubA[38] = (real_t)1.5707963268000000e+00 - tmp; tmp = acadoVariables.x[83] + acadoWorkspace.d[79]; -acadoWorkspace.lbA[39] = (real_t)-4.3633231300000003e-01 - tmp; -acadoWorkspace.ubA[39] = (real_t)4.3633231300000003e-01 - tmp; +acadoWorkspace.lbA[39] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[39] = (real_t)8.7266462600000005e-01 - tmp; } diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.d new file mode 100644 index 00000000000000..2dae4b94389e48 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_solver.o: lib_mpc_export/acado_solver.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.o new file mode 100644 index 00000000000000..f91ea40ab5e655 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.d new file mode 100644 index 00000000000000..752ec5e9f3c686 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.d @@ -0,0 +1,14 @@ +lib_qp/Bounds.o: ../../../../phonelibs/qpoases/SRC/Bounds.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.o new file mode 100644 index 00000000000000..ba30572669f57d Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.d new file mode 100644 index 00000000000000..60295bc07b3dc9 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.d @@ -0,0 +1,14 @@ +lib_qp/Constraints.o: ../../../../phonelibs/qpoases/SRC/Constraints.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.o new file mode 100644 index 00000000000000..d892c668667029 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.d new file mode 100644 index 00000000000000..24145d8ed318e1 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.d @@ -0,0 +1,11 @@ +lib_qp/CyclingManager.o: \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.o new file mode 100644 index 00000000000000..685e25d56b0c62 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.d new file mode 100644 index 00000000000000..77c09376eef96e --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.d @@ -0,0 +1,24 @@ +lib_qp/EXTRAS/SolutionAnalysis.o: \ + ../../../../phonelibs/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.o new file mode 100644 index 00000000000000..987f1e56361641 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.d new file mode 100644 index 00000000000000..6ead64cb9d8ee6 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.d @@ -0,0 +1,10 @@ +lib_qp/Indexlist.o: ../../../../phonelibs/qpoases/SRC/Indexlist.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.o new file mode 100644 index 00000000000000..bd77188d453aae Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.d new file mode 100644 index 00000000000000..b5c6166aba1f64 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.d @@ -0,0 +1,9 @@ +lib_qp/MessageHandling.o: \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.o new file mode 100644 index 00000000000000..87b200d0475adb Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.d new file mode 100644 index 00000000000000..1f6e188af55c17 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.d @@ -0,0 +1,22 @@ +lib_qp/QProblem.o: ../../../../phonelibs/qpoases/SRC/QProblem.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.o new file mode 100644 index 00000000000000..8c179beae1dc8f Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.d new file mode 100644 index 00000000000000..7878a825ce5749 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.d @@ -0,0 +1,16 @@ +lib_qp/QProblemB.o: ../../../../phonelibs/qpoases/SRC/QProblemB.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.o new file mode 100644 index 00000000000000..9c75cb83225246 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.d new file mode 100644 index 00000000000000..c896d9a9faf58d --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.d @@ -0,0 +1,12 @@ +lib_qp/SubjectTo.o: ../../../../phonelibs/qpoases/SRC/SubjectTo.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.o new file mode 100644 index 00000000000000..820c930ce31ec4 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.d new file mode 100644 index 00000000000000..58f35a065397a3 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.d @@ -0,0 +1,8 @@ +lib_qp/Utils.o: ../../../../phonelibs/qpoases/SRC/Utils.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.o new file mode 100644 index 00000000000000..ef645ef188049f Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/libmpc.so b/selfdrive/controls/lib/lateral_mpc/libmpc.so new file mode 100755 index 00000000000000..a0c0dc815d3b10 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/libmpc.so differ diff --git a/selfdrive/controls/lib/lateral_mpc/libmpc_py.py b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py index 33bbe1898f4dfe..1537d2f6c027dd 100644 --- a/selfdrive/controls/lib/lateral_mpc/libmpc_py.py +++ b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py @@ -1,12 +1,11 @@ import os -import sys import subprocess from cffi import FFI mpc_dir = os.path.dirname(os.path.abspath(__file__)) -libmpc_fn = os.path.join(mpc_dir, "libcommampc.so") -subprocess.check_call(["make", "-j4"], stdout=sys.stderr, cwd=mpc_dir) +libmpc_fn = os.path.join(mpc_dir, "libmpc.so") +subprocess.check_call(["make", "-j4"], cwd=mpc_dir) ffi = FFI() ffi.cdef(""" @@ -15,13 +14,14 @@ } state_t; typedef struct { - double x[20]; - double y[20]; - double psi[20]; - double delta[20]; + double x[21]; + double y[21]; + double psi[21]; + double delta[21]; + double cost; } log_t; -void init(double steer_rate_cost); +void init(double pathCost, double laneCost, double headingCost, double steerRateCost); int run_mpc(state_t * x0, log_t * solution, double l_poly[4], double r_poly[4], double p_poly[4], double l_prob, double r_prob, double p_prob, double curvature_factor, double v_ref, double lane_width); diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index 0257898f692ecd..092edd27a1c64d 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -1,28 +1,28 @@ -import numpy as np +from cereal import log from common.numpy_fast import clip, interp -from selfdrive.config import Conversions as CV from selfdrive.controls.lib.pid import PIController +LongCtrlState = log.Live100Data.LongControlState + STOPPING_EGO_SPEED = 0.5 -MIN_CAN_SPEED = 0.3 #TODO: parametrize this in car interface +MIN_CAN_SPEED = 0.3 # TODO: parametrize this in car interface STOPPING_TARGET_SPEED = MIN_CAN_SPEED + 0.01 STARTING_TARGET_SPEED = 0.5 BRAKE_THRESHOLD_TO_PID = 0.2 +STOPPING_BRAKE_RATE = 0.2 # brake_travel/s while trying to stop +STARTING_BRAKE_RATE = 0.8 # brake_travel/s while releasing on restart +BRAKE_STOPPING_TARGET = 0.5 # apply at least this amount of brake to maintain the vehicle stationary -class LongCtrlState: - #*** this function handles the long control state transitions - # long_control_state labels (see capnp enum): - off = 'off' # Off - pid = 'pid' # moving and tracking targets, with PID control running - stopping = 'stopping' # stopping and changing controls to almost open loop as PID does not fit well at such a low speed - starting = 'starting' # starting and releasing brakes in open loop before giving back to PID +_MAX_SPEED_ERROR_BP = [0., 30.] # speed breakpoints +_MAX_SPEED_ERROR_V = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp +RATE = 100.0 def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid, output_gb, brake_pressed, cruise_standstill): - + """Update longitudinal control state machine""" stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ (v_ego < STOPPING_EGO_SPEED and \ ((v_pid < STOPPING_TARGET_SPEED and v_target < STOPPING_TARGET_SPEED) or @@ -55,74 +55,71 @@ def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid, return long_control_state -stopping_brake_rate = 0.2 # brake_travel/s while trying to stop -starting_brake_rate = 0.8 # brake_travel/s while releasing on restart -brake_stopping_target = 0.5 # apply at least this amount of brake to maintain the vehicle stationary - -_MAX_SPEED_ERROR_BP = [0., 30.] # speed breakpoints -_MAX_SPEED_ERROR_V = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp - - class LongControl(object): def __init__(self, CP, compute_gb): self.long_control_state = LongCtrlState.off # initialized to off self.pid = PIController((CP.longitudinalKpBP, CP.longitudinalKpV), (CP.longitudinalKiBP, CP.longitudinalKiV), - rate=100.0, + rate=RATE, sat_limit=0.8, convert=compute_gb) self.v_pid = 0.0 self.last_output_gb = 0.0 def reset(self, v_pid): + """Reset PID controller and change setpoint""" self.pid.reset() self.v_pid = v_pid def update(self, active, v_ego, brake_pressed, standstill, cruise_standstill, v_cruise, v_target, v_target_future, a_target, CP, lead_1): - # actuation limits + """Update longitudinal control. This updates the state machine and runs a PID loop""" + # Actuation limits gas_max = interp(v_ego, CP.gasMaxBP, CP.gasMaxV) brake_max = interp(v_ego, CP.brakeMaxBP, CP.brakeMaxV) + # Update state machine output_gb = self.last_output_gb - rate = 100.0 self.long_control_state = long_control_state_trans(active, self.long_control_state, v_ego, v_target_future, self.v_pid, output_gb, brake_pressed, cruise_standstill) v_ego_pid = max(v_ego, MIN_CAN_SPEED) # Without this we get jumps, CAN bus reports 0 when speed < 0.3 - # *** long control behavior based on state if self.long_control_state == LongCtrlState.off: - self.v_pid = v_ego_pid # do nothing - output_gb = 0. + self.v_pid = v_ego_pid self.pid.reset() + output_gb = 0. # tracking objects and driving elif self.long_control_state == LongCtrlState.pid: - prevent_overshoot = not CP.stoppingControl and v_ego < 1.5 and v_target_future < 0.7 - self.v_pid = v_target self.pid.pos_limit = gas_max self.pid.neg_limit = - brake_max + + # Toyota starts braking more when it thinks you want to stop + # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration + prevent_overshoot = not CP.stoppingControl and v_ego < 1.5 and v_target_future < 0.7 deadzone = interp(v_ego_pid, CP.longPidDeadzoneBP, CP.longPidDeadzoneV) + output_gb = self.pid.update(self.v_pid, v_ego_pid, speed=v_ego_pid, deadzone=deadzone, feedforward=a_target, freeze_integrator=prevent_overshoot) + if prevent_overshoot: output_gb = min(output_gb, 0.0) - # intention is to stop, switch to a different brake control until we stop + # Intention is to stop, switch to a different brake control until we stop elif self.long_control_state == LongCtrlState.stopping: - # TODO: use the standstill bit from CAN to detect movements, usually more accurate than looking at v_ego - if not standstill or output_gb > -brake_stopping_target: - output_gb -= stopping_brake_rate / rate + # Keep applying brakes until the car is stopped + if not standstill or output_gb > -BRAKE_STOPPING_TARGET: + output_gb -= STOPPING_BRAKE_RATE / RATE output_gb = clip(output_gb, -brake_max, gas_max) self.v_pid = v_ego self.pid.reset() - # intention is to move again, release brake fast before handling control to PID + # Intention is to move again, release brake fast before handing control to PID elif self.long_control_state == LongCtrlState.starting: if output_gb < -0.2: - output_gb += starting_brake_rate / rate + output_gb += STARTING_BRAKE_RATE / RATE self.v_pid = v_ego self.pid.reset() diff --git a/selfdrive/controls/lib/longitudinal_mpc/Makefile b/selfdrive/controls/lib/longitudinal_mpc/Makefile index 409715cf17e9d6..17f78eada990df 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/Makefile +++ b/selfdrive/controls/lib/longitudinal_mpc/Makefile @@ -3,6 +3,7 @@ CXX = clang++ PHONELIBS = ../../../../phonelibs +UNAME_S := $(shell uname -s) UNAME_M := $(shell uname -m) CFLAGS = -O3 -fPIC -I. @@ -12,67 +13,61 @@ QPOASES_FLAGS = -I$(PHONELIBS)/qpoases -I$(PHONELIBS)/qpoases/INCLUDE -I$(PHONEL ACADO_FLAGS = -I$(PHONELIBS)/acado/include -I$(PHONELIBS)/acado/include/acado -ifeq ($(UNAME_M),aarch64) -ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +ifeq ($(UNAME_S),Darwin) + ACADO_LIBS := -lacado_toolkit_s +else ifeq ($(UNAME_M),aarch64) + ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a else -ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a + ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a endif OBJS = \ - qp/Bounds.o \ - qp/Constraints.o \ - qp/CyclingManager.o \ - qp/Indexlist.o \ - qp/MessageHandling.o \ - qp/QProblem.o \ - qp/QProblemB.o \ - qp/SubjectTo.o \ - qp/Utils.o \ - qp/EXTRAS/SolutionAnalysis.o \ - mpc_export/acado_qpoases_interface.o \ - mpc_export/acado_integrator.o \ - mpc_export/acado_solver.o \ - mpc_export/acado_auxiliary_functions.o \ - mpc.o + lib_qp/Bounds.o \ + lib_qp/Constraints.o \ + lib_qp/CyclingManager.o \ + lib_qp/Indexlist.o \ + lib_qp/MessageHandling.o \ + lib_qp/QProblem.o \ + lib_qp/QProblemB.o \ + lib_qp/SubjectTo.o \ + lib_qp/Utils.o \ + lib_qp/EXTRAS/SolutionAnalysis.o \ + lib_mpc_export/acado_qpoases_interface.o \ + lib_mpc_export/acado_integrator.o \ + lib_mpc_export/acado_solver.o \ + lib_mpc_export/acado_auxiliary_functions.o \ + longitudinal_mpc.o DEPS := $(OBJS:.o=.d) .PHONY: all -all: libcommampc1.so libcommampc2.so +all: libmpc1.so libmpc2.so -libcommampc1.so: $(OBJS) +libmpc1.so: $(OBJS) $(CXX) -shared -o '$@' $^ -lm -libcommampc2.so: libcommampc1.so - cp libcommampc1.so libcommampc2.so +libmpc2.so: libmpc1.so + cp libmpc1.so libmpc2.so -qp/%.o: $(PHONELIBS)/qpoases/SRC/%.cpp +lib_qp/%.o: $(PHONELIBS)/qpoases/SRC/%.cpp @echo "[ CXX ] $@" - mkdir -p qp + mkdir -p lib_qp/EXTRAS $(CXX) $(CXXFLAGS) -MMD \ - -I mpc_export/ \ - $(QPOASES_FLAGS) \ - -c -o '$@' '$<' - -qp/EXTRAS/%.o: $(PHONELIBS)/qpoases/SRC/EXTRAS/%.cpp - @echo "[ CXX ] $@" - mkdir -p qp/EXTRAS - $(CXX) $(CXXFLAGS) -MMD \ - -I mpc_export/ \ + -I lib_mpc_export/ \ $(QPOASES_FLAGS) \ -c -o '$@' '$<' %.o: %.cpp @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) -MMD \ - -I mpc_export/ \ + -I lib_mpc_export/ \ $(QPOASES_FLAGS) \ -c -o '$@' '$<' %.o: %.c @echo "[ CC ] $@" $(CC) $(CFLAGS) -MMD \ - -I mpc_export/ \ + -I lib_mpc_export/ \ $(QPOASES_FLAGS) \ -c -o '$@' '$<' @@ -89,6 +84,6 @@ generate: generator .PHONY: clean clean: - rm -f libcommampc1.so libcommampc2.so generator $(OBJS) $(DEPS) + rm -f *.so generator $(OBJS) $(DEPS) -include $(DEPS) diff --git a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp index 264a2ae0339313..f5c95394d8d3f1 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp +++ b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp @@ -1,7 +1,6 @@ #include const int controlHorizon = 50; -const double samplingTime = 0.2; using namespace std; @@ -19,15 +18,18 @@ int main( ) DifferentialEquation f; DifferentialState x_ego, v_ego, a_ego; - DifferentialState x_l, v_l, a_l; + DifferentialState x_l, v_l, t; - OnlineData lambda; + OnlineData lambda, a_l_0; Control j_ego; auto desired = 4.0 + RW(v_ego, v_l); auto d_l = x_l - x_ego; + // Directly calculate a_l to prevent instabilites due to discretization + auto a_l = a_l_0 * exp(-lambda * t * t / 2); + // Equations of motion f << dot(x_ego) == v_ego; f << dot(v_ego) == a_ego; @@ -35,14 +37,14 @@ int main( ) f << dot(x_l) == v_l; f << dot(v_l) == a_l; - f << dot(a_l) == -lambda * a_l; + f << dot(t) == 1; // Running cost Function h; h << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired)); - h << (d_l - desired) / (0.1 * v_ego + 0.5); - h << a_ego * (1.0 + v_ego / 10.0); - h << j_ego * (1.0 + v_ego / 10.0); + h << (d_l - desired) / (0.05 * v_ego + 0.5); + 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(4,4); Q.setAll(true); @@ -50,8 +52,8 @@ int main( ) // Terminal cost Function hN; hN << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired)); - hN << (d_l - desired) / (0.1 * v_ego + 0.5); - hN << a_ego * (1.0 + v_ego / 10.0); + hN << (d_l - desired) / (0.05 * v_ego + 0.5); + hN << a_ego * (0.1 * v_ego + 1.0); // Weights are defined in mpc. BMatrix QN(3,3); QN.setAll(true); @@ -77,7 +79,7 @@ int main( ) ocp.minimizeLSQEndTerm(QN, hN); ocp.subjectTo( 0.0 <= v_ego); - ocp.setNOD(1); + ocp.setNOD(2); OCPexport mpc(ocp); mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); @@ -95,7 +97,7 @@ int main( ) mpc.set( GENERATE_MATLAB_INTERFACE, NO ); mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); - if (mpc.exportCode( "mpc_export" ) != SUCCESSFUL_RETURN) + if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) exit( EXIT_FAILURE ); mpc.printDimensionsQP( ); diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_auxiliary_functions.c b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.c similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_auxiliary_functions.c rename to selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.c diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.d new file mode 100644 index 00000000000000..50c6a60d1fb846 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.d @@ -0,0 +1,5 @@ +lib_mpc_export/acado_auxiliary_functions.o: \ + lib_mpc_export/acado_auxiliary_functions.c \ + lib_mpc_export/acado_auxiliary_functions.h \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_auxiliary_functions.h b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.h similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_auxiliary_functions.h rename to selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.o new file mode 100644 index 00000000000000..65182c5bb1ee55 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_common.h b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h similarity index 96% rename from selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_common.h rename to selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h index 2c0ab64ef141c7..cecba6e7408cba 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_common.h +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h @@ -64,7 +64,7 @@ extern "C" /** Number of control/estimation intervals. */ #define ACADO_N 20 /** Number of online data values. */ -#define ACADO_NOD 1 +#define ACADO_NOD 2 /** Number of path constraints. */ #define ACADO_NPAC 0 /** Number of control variables. */ @@ -114,11 +114,11 @@ real_t x[ 126 ]; */ real_t u[ 20 ]; -/** Column vector of size: 21 +/** Matrix of size: 21 x 2 (row major format) * * Matrix containing 21 online data vectors. */ -real_t od[ 21 ]; +real_t od[ 42 ]; /** Column vector of size: 80 * @@ -155,16 +155,19 @@ real_t x0[ 6 ]; */ typedef struct ACADOworkspace_ { +/** Column vector of size: 10 */ +real_t rhs_aux[ 10 ]; + real_t rk_ttt; -/** Row vector of size: 50 */ -real_t rk_xxx[ 50 ]; +/** Row vector of size: 51 */ +real_t rk_xxx[ 51 ]; /** Matrix of size: 4 x 48 (row major format) */ real_t rk_kkk[ 192 ]; -/** Row vector of size: 50 */ -real_t state[ 50 ]; +/** Row vector of size: 51 */ +real_t state[ 51 ]; /** Column vector of size: 120 */ real_t d[ 120 ]; @@ -181,11 +184,11 @@ real_t evGx[ 720 ]; /** Column vector of size: 120 */ real_t evGu[ 120 ]; -/** Column vector of size: 32 */ -real_t objAuxVar[ 32 ]; +/** Column vector of size: 30 */ +real_t objAuxVar[ 30 ]; -/** Row vector of size: 8 */ -real_t objValueIn[ 8 ]; +/** Row vector of size: 9 */ +real_t objValueIn[ 9 ]; /** Row vector of size: 32 */ real_t objValueOut[ 32 ]; diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_integrator.c b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c similarity index 94% rename from selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_integrator.c rename to selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c index 584d8fb857f530..2e77d54147dbee 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_integrator.c +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c @@ -25,14 +25,28 @@ void acado_rhs_forw(const real_t* in, real_t* out) const real_t* xd = in; const real_t* u = in + 48; const real_t* od = in + 49; +/* Vector of auxiliary variables; number of elements: 10. */ +real_t* a = acadoWorkspace.rhs_aux; + +/* Compute intermediate quantities: */ +a[0] = (exp((((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[5])/(real_t)(2.0000000000000000e+00)))); +a[1] = ((real_t)(1.0000000000000000e+00)/(real_t)(2.0000000000000000e+00)); +a[2] = (exp((((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[5])/(real_t)(2.0000000000000000e+00)))); +a[3] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[36])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[36]))*a[1])*a[2]); +a[4] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[37])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[37]))*a[1])*a[2]); +a[5] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[38])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[38]))*a[1])*a[2]); +a[6] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[39])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[39]))*a[1])*a[2]); +a[7] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[40])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[40]))*a[1])*a[2]); +a[8] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[41])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[41]))*a[1])*a[2]); +a[9] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[47])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[47]))*a[1])*a[2]); /* Compute outputs: */ out[0] = xd[1]; out[1] = xd[2]; out[2] = u[0]; out[3] = xd[4]; -out[4] = xd[5]; -out[5] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[5]); +out[4] = (od[1]*a[0]); +out[5] = (real_t)(1.0000000000000000e+00); out[6] = xd[12]; out[7] = xd[13]; out[8] = xd[14]; @@ -57,24 +71,24 @@ out[26] = xd[32]; out[27] = xd[33]; out[28] = xd[34]; out[29] = xd[35]; -out[30] = xd[36]; -out[31] = xd[37]; -out[32] = xd[38]; -out[33] = xd[39]; -out[34] = xd[40]; -out[35] = xd[41]; -out[36] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[36]); -out[37] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[37]); -out[38] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[38]); -out[39] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[39]); -out[40] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[40]); -out[41] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[41]); +out[30] = (od[1]*a[3]); +out[31] = (od[1]*a[4]); +out[32] = (od[1]*a[5]); +out[33] = (od[1]*a[6]); +out[34] = (od[1]*a[7]); +out[35] = (od[1]*a[8]); +out[36] = (real_t)(0.0000000000000000e+00); +out[37] = (real_t)(0.0000000000000000e+00); +out[38] = (real_t)(0.0000000000000000e+00); +out[39] = (real_t)(0.0000000000000000e+00); +out[40] = (real_t)(0.0000000000000000e+00); +out[41] = (real_t)(0.0000000000000000e+00); out[42] = xd[43]; out[43] = xd[44]; out[44] = (real_t)(1.0000000000000000e+00); out[45] = xd[46]; -out[46] = xd[47]; -out[47] = (((real_t)(0.0000000000000000e+00)-od[0])*xd[47]); +out[46] = (od[1]*a[9]); +out[47] = (real_t)(0.0000000000000000e+00); } /* Fixed step size:0.2 */ @@ -130,6 +144,7 @@ rk_eta[46] = 0.0000000000000000e+00; rk_eta[47] = 0.0000000000000000e+00; acadoWorkspace.rk_xxx[48] = rk_eta[48]; acadoWorkspace.rk_xxx[49] = rk_eta[49]; +acadoWorkspace.rk_xxx[50] = rk_eta[50]; for (run1 = 0; run1 < 1; ++run1) { diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.d new file mode 100644 index 00000000000000..7c057e5ec0f3a9 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_integrator.o: lib_mpc_export/acado_integrator.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.o new file mode 100644 index 00000000000000..0008b139779a03 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_qpoases_interface.cpp b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.cpp similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_qpoases_interface.cpp rename to selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.cpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.d new file mode 100644 index 00000000000000..ba3c6ef1c831b7 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.d @@ -0,0 +1,24 @@ +lib_mpc_export/acado_qpoases_interface.o: \ + lib_mpc_export/acado_qpoases_interface.cpp \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp similarity index 100% rename from selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_qpoases_interface.hpp rename to selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.o new file mode 100644 index 00000000000000..ce919eb77f5fa8 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_solver.c b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c similarity index 99% rename from selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_solver.c rename to selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c index 94aef8c05c87ae..676787bbfcbc7b 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/mpc_export/acado_solver.c +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c @@ -45,7 +45,8 @@ acadoWorkspace.state[4] = acadoVariables.x[lRun1 * 6 + 4]; acadoWorkspace.state[5] = acadoVariables.x[lRun1 * 6 + 5]; acadoWorkspace.state[48] = acadoVariables.u[lRun1]; -acadoWorkspace.state[49] = acadoVariables.od[lRun1]; +acadoWorkspace.state[49] = acadoVariables.od[lRun1 * 2]; +acadoWorkspace.state[50] = acadoVariables.od[lRun1 * 2 + 1]; ret = acado_integrate(acadoWorkspace.state, 1, lRun1); @@ -107,7 +108,7 @@ void acado_evaluateLSQ(const real_t* in, real_t* out) { const real_t* xd = in; const real_t* u = in + 6; -/* Vector of auxiliary variables; number of elements: 32. */ +/* Vector of auxiliary variables; number of elements: 30. */ real_t* a = acadoWorkspace.objAuxVar; /* Compute intermediate quantities: */ @@ -137,18 +138,16 @@ a[22] = (((real_t)(2.9999999999999999e-01)*((((real_t)(0.0000000000000000e+00)-( a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]); -a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); +a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[28] = (a[26]*a[26]); a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); -a[30] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.0000000000000000e+01)); -a[31] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.0000000000000000e+01)); /* Compute outputs: */ out[0] = (a[1]-a[3]); -out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); -out[2] = (xd[2]*((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01)))); -out[3] = (u[0]*((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01)))); +out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); +out[2] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); +out[3] = (u[0]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); out[4] = a[6]; out[5] = (a[11]-a[19]); out[6] = (real_t)(0.0000000000000000e+00); @@ -156,19 +155,19 @@ out[7] = a[20]; out[8] = (a[22]-a[25]); out[9] = (real_t)(0.0000000000000000e+00); out[10] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]); -out[11] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(1.0000000000000001e-01))*a[28])); +out[11] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[28])); out[12] = (real_t)(0.0000000000000000e+00); out[13] = a[26]; out[14] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[29])))*a[26]); out[15] = (real_t)(0.0000000000000000e+00); out[16] = (real_t)(0.0000000000000000e+00); -out[17] = (xd[2]*a[30]); -out[18] = ((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01))); +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); out[20] = (real_t)(0.0000000000000000e+00); out[21] = (real_t)(0.0000000000000000e+00); out[22] = (real_t)(0.0000000000000000e+00); -out[23] = (u[0]*a[31]); +out[23] = (u[0]*(real_t)(1.0000000000000001e-01)); out[24] = (real_t)(0.0000000000000000e+00); out[25] = (real_t)(0.0000000000000000e+00); out[26] = (real_t)(0.0000000000000000e+00); @@ -176,13 +175,13 @@ out[27] = (real_t)(0.0000000000000000e+00); out[28] = (real_t)(0.0000000000000000e+00); out[29] = (real_t)(0.0000000000000000e+00); out[30] = (real_t)(0.0000000000000000e+00); -out[31] = ((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01))); +out[31] = (((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; -/* Vector of auxiliary variables; number of elements: 31. */ +/* Vector of auxiliary variables; number of elements: 30. */ real_t* a = acadoWorkspace.objAuxVar; /* Compute intermediate quantities: */ @@ -212,16 +211,15 @@ a[22] = (((real_t)(2.9999999999999999e-01)*((((real_t)(0.0000000000000000e+00)-( a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]); -a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); +a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); a[28] = (a[26]*a[26]); a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); -a[30] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.0000000000000000e+01)); /* Compute outputs: */ out[0] = (a[1]-a[3]); -out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(5.0000000000000000e-01))); -out[2] = (xd[2]*((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01)))); +out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); +out[2] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); out[3] = a[6]; out[4] = (a[11]-a[19]); out[5] = (real_t)(0.0000000000000000e+00); @@ -229,14 +227,14 @@ out[6] = a[20]; out[7] = (a[22]-a[25]); out[8] = (real_t)(0.0000000000000000e+00); out[9] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]); -out[10] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(1.0000000000000001e-01))*a[28])); +out[10] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((xd[4]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[28])); out[11] = (real_t)(0.0000000000000000e+00); out[12] = a[26]; out[13] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(1.8000000000000000e+00))-((xd[4]+xd[4])*a[29])))*a[26]); out[14] = (real_t)(0.0000000000000000e+00); out[15] = (real_t)(0.0000000000000000e+00); -out[16] = (xd[2]*a[30]); -out[17] = ((real_t)(1.0000000000000000e+00)+(xd[1]/(real_t)(1.0000000000000000e+01))); +out[16] = (xd[2]*(real_t)(1.0000000000000001e-01)); +out[17] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)); out[18] = (real_t)(0.0000000000000000e+00); out[19] = (real_t)(0.0000000000000000e+00); out[20] = (real_t)(0.0000000000000000e+00); @@ -385,7 +383,8 @@ acadoWorkspace.objValueIn[3] = acadoVariables.x[runObj * 6 + 3]; acadoWorkspace.objValueIn[4] = acadoVariables.x[runObj * 6 + 4]; acadoWorkspace.objValueIn[5] = acadoVariables.x[runObj * 6 + 5]; acadoWorkspace.objValueIn[6] = acadoVariables.u[runObj]; -acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj * 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[runObj * 2 + 1]; acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); acadoWorkspace.Dy[runObj * 4] = acadoWorkspace.objValueOut[0]; @@ -404,7 +403,8 @@ acadoWorkspace.objValueIn[2] = acadoVariables.x[122]; acadoWorkspace.objValueIn[3] = acadoVariables.x[123]; acadoWorkspace.objValueIn[4] = acadoVariables.x[124]; acadoWorkspace.objValueIn[5] = acadoVariables.x[125]; -acadoWorkspace.objValueIn[6] = acadoVariables.od[20]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[40]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[41]; acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0]; @@ -5205,7 +5205,8 @@ acadoWorkspace.state[3] = acadoVariables.x[index * 6 + 3]; acadoWorkspace.state[4] = acadoVariables.x[index * 6 + 4]; acadoWorkspace.state[5] = acadoVariables.x[index * 6 + 5]; acadoWorkspace.state[48] = acadoVariables.u[index]; -acadoWorkspace.state[49] = acadoVariables.od[index]; +acadoWorkspace.state[49] = acadoVariables.od[index * 2]; +acadoWorkspace.state[50] = acadoVariables.od[index * 2 + 1]; acado_integrate(acadoWorkspace.state, index == 0, index); @@ -5256,7 +5257,8 @@ else { acadoWorkspace.state[48] = acadoVariables.u[19]; } -acadoWorkspace.state[49] = acadoVariables.od[20]; +acadoWorkspace.state[49] = acadoVariables.od[40]; +acadoWorkspace.state[50] = acadoVariables.od[41]; acado_integrate(acadoWorkspace.state, 1, 19); @@ -5331,7 +5333,8 @@ acadoWorkspace.objValueIn[3] = acadoVariables.x[lRun1 * 6 + 3]; acadoWorkspace.objValueIn[4] = acadoVariables.x[lRun1 * 6 + 4]; acadoWorkspace.objValueIn[5] = acadoVariables.x[lRun1 * 6 + 5]; acadoWorkspace.objValueIn[6] = acadoVariables.u[lRun1]; -acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1 * 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[lRun1 * 2 + 1]; acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); acadoWorkspace.Dy[lRun1 * 4] = acadoWorkspace.objValueOut[0] - acadoVariables.y[lRun1 * 4]; @@ -5345,7 +5348,8 @@ acadoWorkspace.objValueIn[2] = acadoVariables.x[122]; acadoWorkspace.objValueIn[3] = acadoVariables.x[123]; acadoWorkspace.objValueIn[4] = acadoVariables.x[124]; acadoWorkspace.objValueIn[5] = acadoVariables.x[125]; -acadoWorkspace.objValueIn[6] = acadoVariables.od[20]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[40]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[41]; acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0] - acadoVariables.yN[0]; acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1] - acadoVariables.yN[1]; diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.d new file mode 100644 index 00000000000000..2dae4b94389e48 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_solver.o: lib_mpc_export/acado_solver.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o new file mode 100644 index 00000000000000..8f2fcfbdf156ea Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.d new file mode 100644 index 00000000000000..752ec5e9f3c686 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.d @@ -0,0 +1,14 @@ +lib_qp/Bounds.o: ../../../../phonelibs/qpoases/SRC/Bounds.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.o new file mode 100644 index 00000000000000..b770e3240eec05 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.d new file mode 100644 index 00000000000000..60295bc07b3dc9 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.d @@ -0,0 +1,14 @@ +lib_qp/Constraints.o: ../../../../phonelibs/qpoases/SRC/Constraints.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.o new file mode 100644 index 00000000000000..4d47fe901918b4 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.d new file mode 100644 index 00000000000000..24145d8ed318e1 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.d @@ -0,0 +1,11 @@ +lib_qp/CyclingManager.o: \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.o new file mode 100644 index 00000000000000..ec3e83d112b8c5 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.d new file mode 100644 index 00000000000000..77c09376eef96e --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.d @@ -0,0 +1,24 @@ +lib_qp/EXTRAS/SolutionAnalysis.o: \ + ../../../../phonelibs/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.o new file mode 100644 index 00000000000000..71cbd4ce3aa5af Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.d new file mode 100644 index 00000000000000..6ead64cb9d8ee6 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.d @@ -0,0 +1,10 @@ +lib_qp/Indexlist.o: ../../../../phonelibs/qpoases/SRC/Indexlist.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.o new file mode 100644 index 00000000000000..9ef68d5bfa7d38 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.d new file mode 100644 index 00000000000000..b5c6166aba1f64 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.d @@ -0,0 +1,9 @@ +lib_qp/MessageHandling.o: \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.o new file mode 100644 index 00000000000000..87b200d0475adb Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.d new file mode 100644 index 00000000000000..1f6e188af55c17 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.d @@ -0,0 +1,22 @@ +lib_qp/QProblem.o: ../../../../phonelibs/qpoases/SRC/QProblem.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.o new file mode 100644 index 00000000000000..81a50555553aa0 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.d new file mode 100644 index 00000000000000..7878a825ce5749 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.d @@ -0,0 +1,16 @@ +lib_qp/QProblemB.o: ../../../../phonelibs/qpoases/SRC/QProblemB.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.o new file mode 100644 index 00000000000000..a850439245f58e Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.d new file mode 100644 index 00000000000000..c896d9a9faf58d --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.d @@ -0,0 +1,12 @@ +lib_qp/SubjectTo.o: ../../../../phonelibs/qpoases/SRC/SubjectTo.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.o new file mode 100644 index 00000000000000..827237a682079f Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.d new file mode 100644 index 00000000000000..58f35a065397a3 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.d @@ -0,0 +1,8 @@ +lib_qp/Utils.o: ../../../../phonelibs/qpoases/SRC/Utils.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.o new file mode 100644 index 00000000000000..ef645ef188049f Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so b/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so new file mode 100755 index 00000000000000..232e9a158b206c Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py index 8020b63c9b5673..658ee1b85bbcfb 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py +++ b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py @@ -1,15 +1,14 @@ import os -import sys import subprocess from cffi import FFI mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__))) -subprocess.check_call(["make", "-j4"], stdout=sys.stderr, cwd=mpc_dir) +subprocess.check_call(["make", "-j4"], cwd=mpc_dir) def _get_libmpc(mpc_id): - libmpc_fn = os.path.join(mpc_dir, "libcommampc%d.so" % mpc_id) + libmpc_fn = os.path.join(mpc_dir, "libmpc%d.so" % mpc_id) ffi = FFI() ffi.cdef(""" @@ -19,19 +18,20 @@ def _get_libmpc(mpc_id): typedef struct { - double x_ego[20]; - double v_ego[20]; - double a_ego[20]; - double j_ego[20]; - double x_l[20]; - double v_l[20]; - double a_l[20]; + double x_ego[21]; + double v_ego[21]; + double a_ego[21]; + double j_ego[21]; + double x_l[21]; + double v_l[21]; + double t[21]; + double cost; } log_t; - void init(); + void init(double ttcCost, double distanceCost, double accelerationCost, double jerkCost); void init_with_simulation(double v_ego, double x_l, double v_l, double a_l, double l); int run_mpc(state_t * x0, log_t * solution, - double l); + double l, double a_l_0); """) return (ffi, ffi.dlopen(libmpc_fn)) diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc.c b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c similarity index 65% rename from selfdrive/controls/lib/longitudinal_mpc/mpc.c rename to selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c index 4e2c13c1a1c7e4..c0b43e53c93771 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/mpc.c +++ b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c @@ -2,6 +2,7 @@ #include "acado_auxiliary_functions.h" #include +#include #define NX ACADO_NX /* Number of differential state variables. */ #define NXA ACADO_NXA /* Number of algebraic variables. */ @@ -22,18 +23,20 @@ typedef struct { typedef struct { - double x_ego[N]; - double v_ego[N]; - double a_ego[N]; - double j_ego[N]; - double x_l[N]; - double v_l[N]; - double a_l[N]; + double x_ego[N+1]; + double v_ego[N+1]; + double a_ego[N+1]; + double j_ego[N+1]; + double x_l[N+1]; + double v_l[N+1]; + double t[N+1]; + double cost; } log_t; -void init(){ +void init(double ttcCost, double distanceCost, double accelerationCost, double jerkCost){ acado_initializeSolver(); int i; + const int STEP_MULTIPLIER = 3; /* Initialize the states and controls. */ for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0; @@ -50,47 +53,60 @@ void init(){ for (i = 0; i < N; i++) { int f = 1; if (i > 4){ - f = 3; + f = STEP_MULTIPLIER; } - acadoVariables.W[16 * i + 0] = 5.0 * f; // exponential cost for danger zone - acadoVariables.W[16 * i + 5] = 0.1 * f; // desired distance - acadoVariables.W[16 * i + 10] = 10.0 * f; // acceleration - acadoVariables.W[16 * i + 15] = 20.0 * f; // jerk + acadoVariables.W[16 * i + 0] = ttcCost * f; // exponential cost for time-to-collision (ttc) + acadoVariables.W[16 * i + 5] = distanceCost * f; // desired distance + acadoVariables.W[16 * i + 10] = accelerationCost * f; // acceleration + acadoVariables.W[16 * i + 15] = jerkCost * f; // jerk } - acadoVariables.WN[0] = 5.0; // exponential cost for danger zone - acadoVariables.WN[4] = 0.1; // desired distance - acadoVariables.WN[8] = 10.0; // acceleration + acadoVariables.WN[0] = ttcCost * STEP_MULTIPLIER; // exponential cost for danger zone + acadoVariables.WN[4] = distanceCost * STEP_MULTIPLIER; // desired distance + acadoVariables.WN[8] = accelerationCost * STEP_MULTIPLIER; // acceleration } -void init_with_simulation(double v_ego, double x_l, double v_l, double a_l, double l){ +void init_with_simulation(double v_ego, double x_l_0, double v_l_0, double a_l_0, double l){ int i; double x_ego = 0.0; double a_ego = 0.0; + double x_l = x_l_0; + double v_l = v_l_0; + double a_l = a_l_0; + + if (v_ego > v_l){ a_ego = -(v_ego - v_l) * (v_ego - v_l) / (2.0 * x_l + 0.01) + a_l; } double dt = 0.2; + double t = 0.; for (i = 0; i < N + 1; ++i){ if (i > 4){ dt = 0.6; } + + // Directly calculate a_l to prevent instabilites due to discretization + a_l = a_l_0 * exp(-l * t * t / 2); + + /* printf("x_e: %.2f\t v_e: %.2f\t a_e: %.2f\t", x_ego, v_ego, a_ego); */ + /* printf("x_l: %.2f\t v_l: %.2f\t a_l: %.2f\n", x_l, v_l, a_l); */ + acadoVariables.x[i*NX] = x_ego; acadoVariables.x[i*NX+1] = v_ego; acadoVariables.x[i*NX+2] = a_ego; acadoVariables.x[i*NX+3] = x_l; acadoVariables.x[i*NX+4] = v_l; - acadoVariables.x[i*NX+5] = a_l; + acadoVariables.x[i*NX+5] = t; x_ego += v_ego * dt; v_ego += a_ego * dt; x_l += v_l * dt; v_l += a_l * dt; - a_l += -l * a_l * dt; + t += dt; if (v_ego <= 0.0) { v_ego = 0.0; @@ -102,11 +118,12 @@ void init_with_simulation(double v_ego, double x_l, double v_l, double a_l, doub for (i = 0; i < NYN; ++i) acadoVariables.yN[ i ] = 0.0; } -int run_mpc(state_t * x0, log_t * solution, double l){ +int run_mpc(state_t * x0, log_t * solution, double l, double a_l_0){ int i; for (i = 0; i <= NOD * N; i+= NOD){ acadoVariables.od[i] = l; + acadoVariables.od[i+1] = a_l_0; } acadoVariables.x[0] = acadoVariables.x0[0] = x0->x_ego; @@ -114,7 +131,7 @@ int run_mpc(state_t * x0, log_t * solution, double l){ acadoVariables.x[2] = acadoVariables.x0[2] = x0->a_ego; acadoVariables.x[3] = acadoVariables.x0[3] = x0->x_l; acadoVariables.x[4] = acadoVariables.x0[4] = x0->v_l; - acadoVariables.x[5] = acadoVariables.x0[5] = x0->a_l; + acadoVariables.x[5] = acadoVariables.x0[5] = 0.0; acado_preparationStep(); acado_feedbackStep(); @@ -125,10 +142,11 @@ int run_mpc(state_t * x0, log_t * solution, double l){ solution->a_ego[i] = acadoVariables.x[i*NX+2]; solution->x_l[i] = acadoVariables.x[i*NX+3]; solution->v_l[i] = acadoVariables.x[i*NX+4]; - solution->a_l[i] = acadoVariables.x[i*NX+5]; + solution->t[i] = acadoVariables.x[i*NX+5]; solution->j_ego[i] = acadoVariables.u[i]; } + solution->cost = acado_getObjective(); // Dont shift states here. Current solution is closer to next timestep than if // we shift by 0.2 seconds. diff --git a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.d b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.d new file mode 100644 index 00000000000000..34a2a0d20ce304 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.d @@ -0,0 +1,3 @@ +longitudinal_mpc.o: longitudinal_mpc.c lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o new file mode 100644 index 00000000000000..e899d7b785a16f Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o differ diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index 68b4f22cfb3963..178b5e6dbb2de4 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -1,6 +1,7 @@ from common.numpy_fast import interp from selfdrive.controls.lib.latcontrol_helpers import model_polyfit, calc_desired_path, compute_path_pinv +CAMERA_OFFSET = 0.06 # m from center car to camera class PathPlanner(object): def __init__(self): @@ -21,6 +22,10 @@ def update(self, v_ego, md): l_poly = model_polyfit(md.model.leftLane.points, self._path_pinv) # left line r_poly = model_polyfit(md.model.rightLane.points, self._path_pinv) # right line + # only offset left and right lane lines; offsetting p_poly does not make sense + l_poly[3] += CAMERA_OFFSET + r_poly[3] += CAMERA_OFFSET + p_prob = 1. # model does not tell this probability yet, so set to 1 for now l_prob = md.model.leftLane.prob # left line prob r_prob = md.model.rightLane.prob # right line prob diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py index 40ae836b9ece5c..b68dc3810eef4b 100644 --- a/selfdrive/controls/lib/pid.py +++ b/selfdrive/controls/lib/pid.py @@ -1,6 +1,5 @@ import numpy as np from common.numpy_fast import clip, interp -import numbers def apply_deadzone(error, deadzone): if error > deadzone: @@ -14,7 +13,7 @@ def apply_deadzone(error, deadzone): class PIController(object): def __init__(self, k_p, k_i, k_f=1., pos_limit=None, neg_limit=None, rate=100, sat_limit=0.8, convert=None): self._k_p = k_p # proportional gain - self._k_i = k_i # integrale gain + self._k_i = k_i # integral gain self.k_f = k_f # feedforward gain self.pos_limit = pos_limit @@ -30,21 +29,11 @@ def __init__(self, k_p, k_i, k_f=1., pos_limit=None, neg_limit=None, rate=100, s @property def k_p(self): - if isinstance(self._k_p, numbers.Number): - kp = self._k_p - else: - kp = interp(self.speed, self._k_p[0], self._k_p[1]) - - return kp + return interp(self.speed, self._k_p[0], self._k_p[1]) @property def k_i(self): - if isinstance(self._k_i, numbers.Number): - ki = self._k_i - else: - ki = interp(self.speed, self._k_i[0], self._k_i[1]) - - return ki + return interp(self.speed, self._k_i[0], self._k_i[1]) def _check_saturation(self, control, override, error): saturated = (control < self.neg_limit) or (control > self.pos_limit) diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index ad304e88424abe..33cb4f56f06d36 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -1,29 +1,30 @@ #!/usr/bin/env python +import os import zmq - -import numpy as np import math +import numpy as np +from copy import copy +from cereal import log from collections import defaultdict - from common.realtime import sec_since_boot -from common.params import Params from common.numpy_fast import interp import selfdrive.messaging as messaging from selfdrive.swaglog import cloudlog from selfdrive.config import Conversions as CV from selfdrive.services import service_list -from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET +from selfdrive.controls.lib.drive_helpers import create_event, MPC_COST_LONG, EventTypes as ET from selfdrive.controls.lib.pathplanner import PathPlanner from selfdrive.controls.lib.longitudinal_mpc import libmpc_py from selfdrive.controls.lib.speed_smoother import speed_smoother from selfdrive.controls.lib.longcontrol import LongCtrlState, MIN_CAN_SPEED +from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU _DT = 0.01 # 100Hz _DT_MPC = 0.2 # 5Hz MAX_SPEED_ERROR = 2.0 AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted -_DEBUG = False -_LEAD_ACCEL_TAU = 1.5 + +GPS_PLANNER_ADDR = "192.168.5.1" # lookup tables VS speed to determine min and max accels in cruise # make sure these accelerations are smaller than mpc limits @@ -32,8 +33,8 @@ # 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., 1., .8, .5, .3] -_A_CRUISE_MAX_V_FOLLOWING = [1.5, 1.5, 1.2, .7, .3] +_A_CRUISE_MAX_V = [1.1, 1.1, .8, .5, .3] +_A_CRUISE_MAX_V_FOLLOWING = [1.6, 1.6, 1.2, .7, .3] _A_CRUISE_MAX_BP = [0., 5., 10., 20., 40.] # Lookup table for turns @@ -43,9 +44,6 @@ _FCW_A_ACT_V = [-3., -2.] _FCW_A_ACT_BP = [0., 30.] -# max acceleration allowed in acc, which happens in restart -A_ACC_MAX = max(_A_CRUISE_MAX_V_FOLLOWING) - def calc_cruise_accel_limits(v_ego, following): a_cruise_min = interp(v_ego, _A_CRUISE_MIN_BP, _A_CRUISE_MIN_V) @@ -62,10 +60,9 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): This function returns a limited long acceleration allowed, depending on the existing lateral acceleration this should avoid accelerating when losing the target in turns """ - deg_to_rad = np.pi / 180. # from can reading to rad a_total_max = interp(v_ego, _A_TOTAL_MAX_BP, _A_TOTAL_MAX_V) - a_y = v_ego**2 * angle_steers * deg_to_rad / (CP.steerRatio * CP.wheelbase) + a_y = v_ego**2 * angle_steers * CV.DEG_TO_RAD / (CP.steerRatio * CP.wheelbase) a_x_allowed = math.sqrt(max(a_total_max**2 - a_y**2, 0.)) a_target[1] = min(a_target[1], a_x_allowed) @@ -110,7 +107,7 @@ def calc_ttc(v_ego, a_ego, x_lead, v_lead, a_lead): def update(self, mpc_solution, cur_time, v_ego, a_ego, x_lead, v_lead, a_lead, y_lead, vlat_lead, fcw_lead, blinkers): mpc_solution_a = list(mpc_solution[0].a_ego) - self.last_min_a = min(mpc_solution_a[1:]) + self.last_min_a = min(mpc_solution_a) self.v_lead_max = max(self.v_lead_max, v_lead) if (fcw_lead > 0.99): @@ -125,7 +122,7 @@ def update(self, mpc_solution, cur_time, v_ego, a_ego, x_lead, v_lead, a_lead, y self.counters['blinkers'] = self.counters['blinkers'] + 10.0 / (20 * 3.0) if not blinkers else 0 a_thr = interp(v_lead, _FCW_A_ACT_BP, _FCW_A_ACT_V) - a_delta = min(mpc_solution_a[1:15]) - min(0.0, a_ego) + a_delta = min(mpc_solution_a[:15]) - min(0.0, a_ego) fcw_allowed = all(c >= 10 for c in self.counters.values()) if (self.last_min_a < -3.0 or a_delta < a_thr) and fcw_allowed and self.last_fcw_time + 5.0 < cur_time: @@ -161,8 +158,8 @@ def send_mpc_solution(self, qp_iterations, calculation_time): 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.aLead = list(self.mpc_solution[0].a_l) - dat.liveLongitudinalMpc.aLeadTau = self.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 = calculation_time @@ -170,13 +167,14 @@ def send_mpc_solution(self, qp_iterations, calculation_time): def setup_mpc(self): ffi, self.libmpc = libmpc_py.get_libmpc(self.mpc_id) - self.libmpc.init() + 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.l = _LEAD_ACCEL_TAU + self.a_lead_tau = _LEAD_ACCEL_TAU def set_cur_state(self, v, a): self.cur_state[0].v_ego = v @@ -191,38 +189,32 @@ def update(self, CS, lead, v_cruise_setpoint): 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 - # Learn if constant acceleration - if abs(a_lead) < 0.5: - self.l = _LEAD_ACCEL_TAU - else: - self.l *= 0.9 - - l = max(self.l, -a_lead / (v_lead + 0.01)) + self.a_lead_tau = max(lead.aLeadTau, (a_lead**2 * math.pi) / (2 * (v_lead + 0.01)**2)) 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, l) + 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 - self.cur_state[0].a_l = a_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 = CS.vEgo + 10.0 - self.cur_state[0].a_l = 0.0 - l = _LEAD_ACCEL_TAU + a_lead = 0.0 + self.a_lead_tau = _LEAD_ACCEL_TAU # Calculate mpc t = sec_since_boot() - n_its = self.libmpc.run_mpc(self.cur_state, self.mpc_solution, l) + n_its = self.libmpc.run_mpc(self.cur_state, self.mpc_solution, self.a_lead_tau, a_lead) duration = int((sec_since_boot() - t) * 1e9) self.send_mpc_solution(n_its, duration) @@ -232,10 +224,10 @@ def update(self, CS, lead, v_cruise_setpoint): self.v_mpc_future = self.mpc_solution[0].v_ego[10] # Reset if NaN or goes through lead car - dls = np.array(list(self.mpc_solution[0].x_l)[1:]) - np.array(list(self.mpc_solution[0].x_ego)[1:]) + dls = np.array(list(self.mpc_solution[0].x_l)) - np.array(list(self.mpc_solution[0].x_ego)) crashing = min(dls) < -50.0 nans = np.any(np.isnan(list(self.mpc_solution[0].v_ego))) - backwards = min(list(self.mpc_solution[0].v_ego)[1:]) < -0.01 + backwards = min(list(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: @@ -243,7 +235,8 @@ def update(self, CS, lead, v_cruise_setpoint): cloudlog.warning("Longitudinal mpc %d reset - backwards: %s crashing: %s nan: %s" % ( self.mpc_id, backwards, crashing, nans)) - self.libmpc.init() + 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 = CS.vEgo self.cur_state[0].a_ego = 0.0 self.v_mpc = CS.vEgo @@ -258,6 +251,12 @@ def __init__(self, CP, fcw_enabled): self.poller = zmq.Poller() self.live20 = messaging.sub_sock(context, service_list['live20'].port, conflate=True, poller=self.poller) self.model = messaging.sub_sock(context, service_list['model'].port, conflate=True, poller=self.poller) + + if os.environ.get('GPS_PLANNER_ACTIVE', False): + self.gps_planner_plan = messaging.sub_sock(context, service_list['gpsPlannerPlan'].port, conflate=True, poller=self.poller, addr=GPS_PLANNER_ADDR) + else: + self.gps_planner_plan = None + self.plan = messaging.pub_sock(context, service_list['plan'].port) self.live_longitudinal_mpc = messaging.pub_sock(context, service_list['liveLongitudinalMpc'].port) @@ -292,6 +291,10 @@ def __init__(self, CP, fcw_enabled): self.fcw_checker = FCWChecker() self.fcw_enabled = fcw_enabled + self.last_gps_planner_plan = None + self.gps_planner_active = False + self.perception_state = log.Live20Data.new_message() + def choose_solution(self, v_cruise_setpoint, enabled): if enabled: solutions = {'cruise': self.v_cruise} @@ -302,10 +305,11 @@ def choose_solution(self, v_cruise_setpoint, enabled): slowest = min(solutions, key=solutions.get) - if _DEBUG: - print "D_SOL", solutions, slowest, self.v_acc_sol, self.a_acc_sol - print "D_V", self.mpc1.v_mpc, self.mpc2.v_mpc, self.v_cruise - print "D_A", self.mpc1.a_mpc, self.mpc2.a_mpc, self.a_cruise + """ + print "D_SOL", solutions, slowest, self.v_acc_sol, self.a_acc_sol + print "D_V", self.mpc1.v_mpc, self.mpc2.v_mpc, self.v_cruise + print "D_A", self.mpc1.a_mpc, self.mpc2.a_mpc, self.a_cruise + """ self.longitudinalPlanSource = slowest @@ -323,18 +327,24 @@ def choose_solution(self, v_cruise_setpoint, enabled): self.v_acc_future = min([self.mpc1.v_mpc_future, self.mpc2.v_mpc_future, v_cruise_setpoint]) # this runs whenever we get a packet that can change the plan - def update(self, CS, LoC, v_cruise_kph, user_distracted): + def update(self, CS, LaC, LoC, v_cruise_kph, force_slow_decel): cur_time = sec_since_boot() v_cruise_setpoint = v_cruise_kph * CV.KPH_TO_MS md = None l20 = None + gps_planner_plan = None for socket, event in self.poller.poll(0): if socket is self.model: md = messaging.recv_one(socket) elif socket is self.live20: l20 = messaging.recv_one(socket) + elif socket is self.gps_planner_plan: + gps_planner_plan = messaging.recv_one(socket) + + if gps_planner_plan is not None: + self.last_gps_planner_plan = gps_planner_plan if md is not None: self.last_md_ts = md.logMonoTime @@ -343,7 +353,19 @@ def update(self, CS, LoC, v_cruise_kph, user_distracted): self.PP.update(CS.vEgo, md) + if self.last_gps_planner_plan is not None: + plan = self.last_gps_planner_plan.gpsPlannerPlan + self.gps_planner_active = plan.valid + if plan.valid: + self.PP.d_poly = plan.poly + self.PP.p_poly = plan.poly + self.PP.c_poly = plan.poly + self.PP.l_prob = 0.0 + self.PP.r_prob = 0.0 + self.PP.c_prob = 1.0 + if l20 is not None: + self.perception_state = copy(l20.live20) self.last_l20_ts = l20.logMonoTime self.last_l20 = cur_time self.radar_dead = False @@ -366,8 +388,9 @@ def update(self, CS, LoC, v_cruise_kph, user_distracted): # TODO: make a separate lookup for jerk tuning jerk_limits = [min(-0.1, accel_limits[0]), max(0.1, accel_limits[1])] accel_limits = limit_accel_in_turns(CS.vEgo, CS.steeringAngle, accel_limits, self.CP) - if user_distracted: - # if user is not responsive to awareness alerts, then start a smooth deceleration + + if force_slow_decel: + # if required so, force a smooth deceleration accel_limits[1] = min(accel_limits[1], AWARENESS_DECEL) accel_limits[0] = min(accel_limits[0], accel_limits[1]) @@ -426,9 +449,11 @@ def update(self, CS, LoC, v_cruise_kph, user_distracted): if self.model_dead: events.append(create_event('modelCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if self.radar_dead or 'commIssue' in self.radar_errors: - events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if 'fault' in self.radar_errors: - events.append(create_event('radarFault', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + events.append(create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if LaC.mpc_solution[0].cost > 10000. or LaC.mpc_nans: # TODO: find a better way to detect when MPC did not converge + events.append(create_event('plannerError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) # Interpolation of trajectory dt = min(cur_time - self.acc_start_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps @@ -454,6 +479,8 @@ def update(self, CS, LoC, v_cruise_kph, user_distracted): plan_send.plan.hasLead = self.mpc1.prev_lead_status plan_send.plan.longitudinalPlanSource = self.longitudinalPlanSource + plan_send.plan.gpsPlannerActive = self.gps_planner_active + # Send out fcw fcw = self.fcw and (self.fcw_enabled or LoC.long_control_state != LongCtrlState.off) plan_send.plan.fcw = fcw diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index 6dbb72c5c40972..da7d3f71ba0c4d 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -1,12 +1,12 @@ import os import sys -import math import platform import numpy as np from common.numpy_fast import clip, interp from common.kalman.simple_kalman import KF1D +_LEAD_ACCEL_TAU = 1.5 NO_FUSION_SCORE = 100 # bad default fusion score # radar tracks @@ -26,12 +26,14 @@ v_ego_stationary = 4. # no stationary object flag below this speed # Lead Kalman Filter params -_VLEAD_A = np.matrix([[1.0, ts], [0.0, 1.0]]) -_VLEAD_C = np.matrix([1.0, 0.0]) +_VLEAD_A = [[1.0, ts], [0.0, 1.0]] +_VLEAD_C = [[1.0, 0.0]] #_VLEAD_Q = np.matrix([[10., 0.0], [0.0, 100.]]) #_VLEAD_R = 1e3 #_VLEAD_K = np.matrix([[ 0.05705578], [ 0.03073241]]) -_VLEAD_K = np.matrix([[ 0.1988689 ], [ 0.28555364]]) +_VLEAD_K = [[ 0.1988689 ], [ 0.28555364]] + +RDR_TO_LDR = 2.7 class Track(object): @@ -42,6 +44,7 @@ def __init__(self): def update(self, d_rel, y_rel, v_rel, d_path, v_ego_t_aligned, measured, steer_override): if self.initted: + # pylint: disable=access-member-before-definition self.dPathPrev = self.dPath self.vLeadPrev = self.vLead self.vRelPrev = self.vRel @@ -60,12 +63,13 @@ def update(self, d_rel, y_rel, v_rel, d_path, v_ego_t_aligned, measured, steer_o if not self.initted: self.initted = True + self.aLeadTau = _LEAD_ACCEL_TAU self.cnt = 1 self.vision_cnt = 0 self.vision = False self.aRel = 0. # nidec gives no information about this self.vLat = 0. - self.kf = KF1D(np.matrix([[self.vLead], [0.0]]), _VLEAD_A, _VLEAD_C, _VLEAD_K) + self.kf = KF1D([[self.vLead], [0.0]], _VLEAD_A, _VLEAD_C, _VLEAD_K) else: # estimate acceleration # TODO: use Kalman filter @@ -82,8 +86,8 @@ def update(self, d_rel, y_rel, v_rel, d_path, v_ego_t_aligned, measured, steer_o self.cnt += 1 - self.vLeadK = float(self.kf.x[SPEED]) - self.aLeadK = float(self.kf.x[ACCEL]) + self.vLeadK = float(self.kf.x[SPEED][0]) + self.aLeadK = float(self.kf.x[ACCEL][0]) if self.stationary: # stationary objects can become non stationary, but not the other way around @@ -92,6 +96,12 @@ def update(self, d_rel, y_rel, v_rel, d_path, v_ego_t_aligned, measured, steer_o self.vision_score = NO_FUSION_SCORE + # Learn if constant acceleration + if abs(self.aLeadK) < 0.5: + self.aLeadTau = _LEAD_ACCEL_TAU + else: + self.aLeadTau *= 0.9 + def update_vision_score(self, dist_to_vision, rel_speed_diff): # rel speed is very hard to estimate from vision if dist_to_vision < 4.0 and rel_speed_diff < 10.: @@ -110,18 +120,19 @@ def get_key_for_cluster(self): # Weigh y higher since radar is inaccurate in this dimension return [self.dRel, self.yRel*2, self.vRel] -# ******************* Cluster ******************* +# ******************* Cluster ******************* if platform.machine() == 'aarch64': for x in sys.path: pp = os.path.join(x, "phonelibs/hierarchy/lib") if os.path.isfile(os.path.join(pp, "_hierarchy.so")): sys.path.append(pp) break - import _hierarchy + import _hierarchy #pylint: disable=import-error else: from scipy.cluster import _hierarchy + def fcluster(Z, t, criterion='inconsistent', depth=2, R=None, monocrit=None): # supersimplified function to get fast clustering. Got it from scipy Z = np.asarray(Z, order='c') @@ -130,10 +141,10 @@ def fcluster(Z, t, criterion='inconsistent', depth=2, R=None, monocrit=None): _hierarchy.cluster_dist(Z, T, float(t), int(n)) return T -RDR_TO_LDR = 2.7 def mean(l): - return sum(l)/len(l) + return sum(l) / len(l) + class Cluster(object): def __init__(self): @@ -180,6 +191,10 @@ def vLeadK(self): def aLeadK(self): return mean([t.aLeadK for t in self.tracks]) + @property + def aLeadTau(self): + return mean([t.aLeadTau for t in self.tracks]) + @property def vision(self): return any([t.vision for t in self.tracks]) @@ -200,21 +215,24 @@ def stationary(self): def oncoming(self): return all([t.oncoming for t in self.tracks]) - def toLive20(self, lead): - lead.dRel = float(self.dRel) - RDR_TO_LDR - lead.yRel = float(self.yRel) - lead.vRel = float(self.vRel) - lead.aRel = float(self.aRel) - lead.vLead = float(self.vLead) - lead.dPath = float(self.dPath) - lead.vLat = float(self.vLat) - lead.vLeadK = float(self.vLeadK) - lead.aLeadK = float(self.aLeadK) - lead.status = True - lead.fcw = self.is_potential_fcw() + def toLive20(self): + return { + "dRel": float(self.dRel) - RDR_TO_LDR, + "yRel": float(self.yRel), + "vRel": float(self.vRel), + "aRel": float(self.aRel), + "vLead": float(self.vLead), + "dPath": float(self.dPath), + "vLat": float(self.vLat), + "vLeadK": float(self.vLeadK), + "aLeadK": float(self.aLeadK), + "status": True, + "fcw": self.is_potential_fcw(), + "aLeadTau": float(self.aLeadTau) + } def __str__(self): - ret = "x: %4.1f y: %4.1f v: %4.1f a: %4.1f d: %4.2f" % (self.dRel, self.yRel, self.vRel, self.aRel, self.dPath) + ret = "x: %4.1f y: %4.1f v: %4.1f a: %4.1f d: %4.2f" % (self.dRel, self.yRel, self.vRel, self.aLeadK, self.dPath) if self.stationary: ret += " stationary" if self.vision: diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py index f10e31a3b8d678..95e3ef37832d87 100755 --- a/selfdrive/controls/lib/vehicle_model.py +++ b/selfdrive/controls/lib/vehicle_model.py @@ -1,16 +1,42 @@ #!/usr/bin/env python import numpy as np -from numpy.linalg import inv +from numpy.linalg import solve -# dynamic bycicle model from "The Science of Vehicle Dynamics (2014), M. Guiggiani"## -# Xdot = A*X + B*U -# where X = [v, r], with v and r lateral speed and rotational speed, respectively -# and U is the steering angle (controller input) -# -# A depends on longitudinal speed, u, and vehicle parameters CP +""" +Dynamic bycicle model from "The Science of Vehicle Dynamics (2014), M. Guiggiani" + +The state is x = [v, r]^T +with v lateral speed [m/s], and r rotational speed [rad/s] + +The input u is the steering angle [rad] + +The system is defined by +x_dot = A*x + B*u + +A depends on longitudinal speed, u [m/s], and vehicle parameters CP +""" def create_dyn_state_matrices(u, VM): + """Returns the A and B matrix for the dynamics system + + Args: + u: Vehicle speed [m/s] + VM: Vehicle model + + Returns: + A tuple with the 2x2 A matrix, and 2x1 B matrix + + Parameters in the vehicle model: + cF: Tire stiffnes Front [N/rad] + cR: Tire stiffnes Front [N/rad] + aF: Distance from CG to front wheels [m] + aR: Distance from CG to rear wheels [m] + m: Mass [kg] + j: Rotational inertia [kg m^2] + sR: Steering ratio [-] + chi: Steer ratio rear [-] + """ A = np.zeros((2, 2)) B = np.zeros((2, 1)) A[0, 0] = - (VM.cF + VM.cR) / (VM.m * u) @@ -23,7 +49,18 @@ def create_dyn_state_matrices(u, VM): def kin_ss_sol(sa, u, VM): - # kinematic solution, useful when speed ~ 0 + """Calculate the steady state solution at low speeds + At low speeds the tire slip is undefined, so a kinematic + model is used. + + Args: + sa: Steering angle [rad] + u: Speed [m/s] + VM: Vehicle model + + Returns: + 2x1 matrix with steady state solution + """ K = np.zeros((2, 1)) K[0, 0] = VM.aR / VM.sR / VM.l * u K[1, 0] = 1. / VM.sR / VM.l * u @@ -31,25 +68,34 @@ def kin_ss_sol(sa, u, VM): def dyn_ss_sol(sa, u, VM): - # Dynamic solution, useful when speed > 0 + """Calculate the steady state solution when x_dot = 0, + Ax + Bu = 0 => x = A^{-1} B u + + Args: + sa: Steering angle [rad] + u: Speed [m/s] + VM: Vehicle model + + Returns: + 2x1 matrix with steady state solution + """ A, B = create_dyn_state_matrices(u, VM) - return - np.matmul(inv(A), B) * sa + return -solve(A, B) * sa def calc_slip_factor(VM): - # the slip factor is a measure of how the curvature changes with speed - # it's positive for Oversteering vehicle, negative (usual case) otherwise + """The slip factor is a measure of how the curvature changes with speed + it's positive for Oversteering vehicle, negative (usual case) otherwise. + """ return VM.m * (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.l**2 * VM.cF * VM.cR) class VehicleModel(object): - def __init__(self, CP, init_state=np.asarray([[0.], [0.]])): - self.dt = 0.1 - lookahead = 2. # s - self.steps = int(lookahead / self.dt) - self.update_state(init_state) - self.state_pred = np.zeros((self.steps, self.state.shape[0])) - self.CP = CP + def __init__(self, CP): + """ + Args: + CP: Car Parameters + """ # for math readability, convert long names car params into short names self.m = CP.mass self.j = CP.rotationalInertia @@ -61,43 +107,80 @@ def __init__(self, CP, init_state=np.asarray([[0.], [0.]])): self.sR = CP.steerRatio self.chi = CP.steerRatioRear - def update_state(self, state): - self.state = state - def steady_state_sol(self, sa, u): - # if the speed is too small we can't use the dynamic model - # (tire slip is undefined), we then use the kinematic model + """Returns the steady state solution. + + If the speed is too small we can't use the dynamic model (tire slip is undefined), + we then have to use the kinematic model + + Args: + sa: Steering wheel angle [rad] + u: Speed [m/s] + + Returns: + 2x1 matrix with steady state solution (lateral speed, rotational speed) + """ if u > 0.1: return dyn_ss_sol(sa, u, self) else: return kin_ss_sol(sa, u, self) def calc_curvature(self, sa, u): - # this formula can be derived from state equations in steady state conditions + """Returns the curvature. Multiplied by the speed this will give the yaw rate. + + Args: + sa: Steering wheel angle [rad] + u: Speed [m/s] + + Returns: + Curvature factor [rad/m] + """ return self.curvature_factor(u) * sa / self.sR def curvature_factor(self, u): + """Returns the curvature factor. + Multiplied by wheel angle (not steering wheel angle) this will give the curvature. + + Args: + u: Speed [m/s] + + Returns: + Curvature factor [1/m] + """ sf = calc_slip_factor(self) - return (1. - self.chi)/(1. - sf * u**2) / self.l + return (1. - self.chi) / (1. - sf * u**2) / self.l def get_steer_from_curvature(self, curv, u): - return curv * self.sR * 1.0 / self.curvature_factor(u) + """Calculates the required steering wheel angle for a given curvature + + Args: + curv: Desired curvature [rad/s] + u: Speed [m/s] - def state_prediction(self, sa, u): - # U is the matrix of the controls - # u is the long speed - A, B = create_dyn_state_matrices(u, self) - return np.matmul((A * self.dt + np.identity(2)), self.state) + B * sa * self.dt + Returns: + Steering wheel angle [rad] + """ + + return curv * self.sR * 1.0 / self.curvature_factor(u) def yaw_rate(self, sa, u): + """Calculate yaw rate + + Args: + sa: Steering wheel angle [rad] + u: Speed [m/s] + + Returns: + Yaw rate [rad/s] + """ return self.calc_curvature(sa, u) * u + if __name__ == '__main__': + import math from selfdrive.car.honda.interface import CarInterface - # load car params - #CP = CarInterface.get_params("TOYOTA PRIUS 2017", {}) - CP = CarInterface.get_params("HONDA CIVIC 2016 TOURING", {}) - print CP + from selfdrive.car.honda.values import CAR + + CP = CarInterface.get_params(CAR.CIVIC, {}) VM = VehicleModel(CP) - print VM.steady_state_sol(.1, 0.15) - print calc_slip_factor(VM) + print(VM.yaw_rate(math.radians(20), 10.)) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 72e98d732d1680..b909b4952af7be 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -1,8 +1,9 @@ #!/usr/bin/env python -import os +import gc import zmq import numpy as np import numpy.matlib +import importlib from collections import defaultdict from fastcluster import linkage_vector import selfdrive.messaging as messaging @@ -15,7 +16,7 @@ from selfdrive.swaglog import cloudlog from cereal import car from common.params import Params -from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper +from common.realtime import set_realtime_priority, Ratekeeper from common.kalman.ekf import EKF, SimpleSensor DEBUG = False @@ -25,10 +26,11 @@ XV, SPEEDV = 0, 1 VISION_POINT = -1 + class EKFV1D(EKF): def __init__(self): super(EKFV1D, self).__init__(False) - self.identity = np.matlib.identity(DIMSV) + self.identity = numpy.matlib.identity(DIMSV) self.state = np.matlib.zeros((DIMSV, 1)) self.var_init = 1e2 # ~ model variance when probability is 70%, so good starting point self.covar = self.identity * self.var_init @@ -44,19 +46,19 @@ def calc_transfer_fun(self, dt): # fuses camera and radar data for best lead detection def radard_thread(gctx=None): + gc.disable() set_realtime_priority(2) # wait for stats about the car to come in from controls cloudlog.info("radard is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) - mocked= CP.radarName == "mock" + mocked = CP.carName == "mock" VM = VehicleModel(CP) cloudlog.info("radard got CarParams") # import the radar from the fingerprint - cloudlog.info("radard is importing %s", CP.radarName) - exec('from selfdrive.radar.'+CP.radarName+'.interface import RadarInterface') - + cloudlog.info("radard is importing %s", CP.carName) + RadarInterface = importlib.import_module('selfdrive.car.%s.radar_interface' % CP.carName).RadarInterface context = zmq.Context() # *** subscribe to features and model from visiond @@ -65,7 +67,7 @@ def radard_thread(gctx=None): live100 = messaging.sub_sock(context, service_list['live100'].port, conflate=True, poller=poller) PP = PathPlanner() - RI = RadarInterface() + RI = RadarInterface(CP) last_md_ts = 0 last_l100_ts = 0 @@ -136,14 +138,24 @@ def radard_thread(gctx=None): # run kalman filter only if prob is high enough if PP.lead_prob > 0.7: - ekfv.update(speedSensorV.read(PP.lead_dist, covar=PP.lead_var)) + reading = speedSensorV.read(PP.lead_dist, covar=np.matrix(PP.lead_var)) + ekfv.update_scalar(reading) ekfv.predict(tsv) + + # When changing lanes the distance to the lead car can suddenly change, + # which makes the Kalman filter output large relative acceleration + if mocked and abs(PP.lead_dist - ekfv.state[XV]) > 2.0: + ekfv.state[XV] = PP.lead_dist + ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init])) + ekfv.state[SPEEDV] = 0. + ar_pts[VISION_POINT] = (float(ekfv.state[XV]), np.polyval(PP.d_poly, float(ekfv.state[XV])), float(ekfv.state[SPEEDV]), False) else: ekfv.state[XV] = PP.lead_dist ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init])) ekfv.state[SPEEDV] = 0. + if VISION_POINT in ar_pts: del ar_pts[VISION_POINT] @@ -196,9 +208,9 @@ def radard_thread(gctx=None): tracks[fused_id].update_vision_fusion() if DEBUG: - print "NEW CYCLE" + print("NEW CYCLE") if VISION_POINT in ar_pts: - print "vision", ar_pts[VISION_POINT] + print("vision", ar_pts[VISION_POINT]) idens = tracks.keys() track_pts = np.array([tracks[iden].get_key_for_cluster() for iden in idens]) @@ -224,7 +236,7 @@ def radard_thread(gctx=None): if DEBUG: for i in clusters: - print i + print(i) # *** extract the lead car *** lead_clusters = [c for c in clusters if c.is_potential_lead(v_ego)] @@ -245,9 +257,9 @@ def radard_thread(gctx=None): dat.live20.radarErrors = list(rr.errors) dat.live20.l100MonoTime = last_l100_ts if lead_len > 0: - lead_clusters[0].toLive20(dat.live20.leadOne) + dat.live20.leadOne = lead_clusters[0].toLive20() if lead2_len > 0: - lead2_clusters[0].toLive20(dat.live20.leadTwo) + dat.live20.leadTwo = lead2_clusters[0].toLive20() else: dat.live20.leadTwo.status = False else: @@ -262,19 +274,22 @@ def radard_thread(gctx=None): for cnt, ids in enumerate(tracks.keys()): if DEBUG: - print "id: %4.0f x: %4.1f y: %4.1f vr: %4.1f d: %4.1f va: %4.1f vl: %4.1f vlk: %4.1f alk: %4.1f s: %1.0f" % \ + print("id: %4.0f x: %4.1f y: %4.1f vr: %4.1f d: %4.1f va: %4.1f vl: %4.1f vlk: %4.1f alk: %4.1f s: %1.0f v: %1.0f" % \ (ids, tracks[ids].dRel, tracks[ids].yRel, tracks[ids].vRel, tracks[ids].dPath, tracks[ids].vLat, tracks[ids].vLead, tracks[ids].vLeadK, tracks[ids].aLeadK, - tracks[ids].stationary) - dat.liveTracks[cnt].trackId = ids - dat.liveTracks[cnt].dRel = float(tracks[ids].dRel) - dat.liveTracks[cnt].yRel = float(tracks[ids].yRel) - dat.liveTracks[cnt].vRel = float(tracks[ids].vRel) - dat.liveTracks[cnt].aRel = float(tracks[ids].aRel) - dat.liveTracks[cnt].stationary = tracks[ids].stationary - dat.liveTracks[cnt].oncoming = tracks[ids].oncoming + tracks[ids].stationary, + tracks[ids].measured)) + dat.liveTracks[cnt] = { + "trackId": ids, + "dRel": float(tracks[ids].dRel), + "yRel": float(tracks[ids].yRel), + "vRel": float(tracks[ids].vRel), + "aRel": float(tracks[ids].aRel), + "stationary": bool(tracks[ids].stationary), + "oncoming": bool(tracks[ids].oncoming), + } liveTracks.send(dat.to_bytes()) rk.monitor_time() diff --git a/selfdrive/crash.py b/selfdrive/crash.py index 18c27ec1f505cc..20003ee9faff57 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -1,6 +1,7 @@ """Install exception handler for process crash.""" import os import sys +from selfdrive.version import version, dirty from selfdrive.swaglog import cloudlog @@ -16,9 +17,8 @@ def install(): else: from raven import Client from raven.transport.http import HTTPTransport - client = Client('https://1994756b5e6f41cf939a4c65de45f4f2:cefebaf3a8aa40d182609785f7189bd7@app.getsentry.com/77924', - install_sys_hook=False, transport=HTTPTransport) + install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty}) def capture_exception(*args, **kwargs): client.captureException(*args, **kwargs) diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py index 115b54ea60f4ea..d7cbabe63ac139 100755 --- a/selfdrive/debug/can_printer.py +++ b/selfdrive/debug/can_printer.py @@ -1,7 +1,6 @@ #!/usr/bin/env python import os import sys -import struct from collections import defaultdict from common.realtime import sec_since_boot import zmq @@ -9,7 +8,7 @@ from selfdrive.services import service_list -def can_printer(bus=0, max_msg=0x10000, addr="127.0.0.1"): +def can_printer(bus=0, max_msg=None, addr="127.0.0.1"): context = zmq.Context() logcan = messaging.sub_sock(context, service_list['can'].port, addr=addr) @@ -28,7 +27,7 @@ def can_printer(bus=0, max_msg=0x10000, addr="127.0.0.1"): dd = chr(27) + "[2J" dd += "%5.2f\n" % (sec_since_boot() - start) for k,v in sorted(zip(msgs.keys(), map(lambda x: x[-1].encode("hex"), msgs.values()))): - if k < max_msg: + if max_msg is None or k < max_msg: dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) print dd lp = sec_since_boot() diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index a58ac3a5157602..80ac6e4b50859a 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -4,39 +4,80 @@ import zmq import json from hexdump import hexdump +from threading import Thread +from cereal import log import selfdrive.messaging as messaging from selfdrive.services import service_list +def run_server(socketio): + socketio.run(app, host='0.0.0.0', port=4000) + if __name__ == "__main__": context = zmq.Context() poller = zmq.Poller() parser = argparse.ArgumentParser(description='Sniff a communcation socket') + parser.add_argument('--pipe', action='store_true') parser.add_argument('--raw', action='store_true') parser.add_argument('--json', action='store_true') + parser.add_argument('--dump-json', action='store_true') + parser.add_argument('--no-print', action='store_true') + parser.add_argument('--proxy', action='store_true', help='republish on localhost') + parser.add_argument('--map', action='store_true') parser.add_argument('--addr', default='127.0.0.1') parser.add_argument("socket", type=str, nargs='*', help="socket name") args = parser.parse_args() + republish_socks = {} + for m in args.socket if len(args.socket) > 0 else service_list: if m in service_list: - messaging.sub_sock(context, service_list[m].port, poller, addr=args.addr) + port = service_list[m].port elif m.isdigit(): - messaging.sub_sock(context, int(m), poller, addr=args.addr) + port = int(m) else: print("service not found") exit(-1) + sock = messaging.sub_sock(context, port, poller, addr=args.addr) + if args.proxy: + republish_socks[sock] = messaging.pub_sock(context, port) + + if args.map: + from flask.ext.socketio import SocketIO #pylint: disable=no-name-in-module, import-error + from flask import Flask + app = Flask(__name__) + socketio = SocketIO(app, async_mode='threading') + server_thread = Thread(target=run_server, args=(socketio,)) + server_thread.daemon = True + server_thread.start() + print 'server running' while 1: polld = poller.poll(timeout=1000) for sock, mode in polld: if mode != zmq.POLLIN: continue - if args.raw: - hexdump(sock.recv()) - elif args.json: - print(json.loads(sock.recv())) - else: - print messaging.recv_one(sock) - + msg = sock.recv() + evt = log.Event.from_bytes(msg) + if sock in republish_socks: + republish_socks[sock].send(msg) + if args.map and evt.which() == 'liveLocation': + print 'send loc' + socketio.emit('location', { + 'lat': evt.liveLocation.lat, + 'lon': evt.liveLocation.lon, + 'alt': evt.liveLocation.alt, + }) + if not args.no_print: + if args.pipe: + sys.stdout.write(msg) + sys.stdout.flush() + elif args.raw: + hexdump(msg) + elif args.json: + print(json.loads(msg)) + elif args.dump_json: + print json.dumps(evt.to_dict()) + else: + print evt diff --git a/selfdrive/debug/get_fingerprint.py b/selfdrive/debug/get_fingerprint.py new file mode 100755 index 00000000000000..dd8eb4d8088dd4 --- /dev/null +++ b/selfdrive/debug/get_fingerprint.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python + +# simple script to get a vehicle fingerprint. + +# Instructions: +# - connect to a Panda +# - run selfdrive/boardd/boardd +# - launching this script +# - since some messages are published at low frequency, keep this script running for few +# seconds, until all messages are received at least once + +import zmq +import selfdrive.messaging as messaging +from selfdrive.services import service_list + +context = zmq.Context() +logcan = messaging.sub_sock(context, service_list['can'].port) +msgs = {} +while True: + lc = messaging.recv_sock(logcan, True) + for c in lc.can: + # read also msgs sent by EON on CAN bus 0x80 and filter out the + # addr with more than 11 bits + if c.src%0x80 == 0 and c.address < 0x800: + msgs[c.address] = len(c.dat) + + fingerprint = ', '.join("%d: %d" % v for v in sorted(msgs.items())) + + print "number of messages:", len(msgs) + print "fingerprint", fingerprint diff --git a/selfdrive/debug/getframes/getframes.py b/selfdrive/debug/getframes/getframes.py index 498716faf1dbee..292368d6a97ea6 100755 --- a/selfdrive/debug/getframes/getframes.py +++ b/selfdrive/debug/getframes/getframes.py @@ -1,9 +1,7 @@ #!/usr/bin/env python import os -import time import subprocess from cffi import FFI -import ctypes import numpy as np @@ -16,9 +14,10 @@ ffi.cdef(""" typedef enum VisionStreamType { - VISION_STREAM_UI_BACK, - VISION_STREAM_UI_FRONT, + VISION_STREAM_RGB_BACK, + VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV, + VISION_STREAM_YUV_FRONT, VISION_STREAM_MAX, } VisionStreamType; @@ -49,12 +48,15 @@ } VIPCBuf; typedef struct VIPCBufExtra { - uint32_t frame_id; // only for yuv + // only for yuv + uint32_t frame_id; + uint64_t timestamp_eof; } VIPCBufExtra; typedef struct VisionStream { int ipc_fd; int last_idx; + int last_type; int num_bufs; VisionStreamBufs bufs_info; VIPCBuf *bufs; @@ -70,10 +72,16 @@ clib = ffi.dlopen(os.path.join(gf_dir, "libvisionipc.so")) -def getframes(): +def getframes(front=False): s = ffi.new("VisionStream*") buf_info = ffi.new("VisionStreamBufs*") - err = clib.visionstream_init(s, clib.VISION_STREAM_UI_BACK, True, buf_info) + + if front: + stream_type = clib.VISION_STREAM_RGB_FRONT + else: + stream_type = clib.VISION_STREAM_RGB_BACK + + err = clib.visionstream_init(s, stream_type, True, buf_info) assert err == 0 w = buf_info.width diff --git a/selfdrive/debug/test_carcontroller.py b/selfdrive/debug/test_carcontroller.py deleted file mode 100755 index d672cfb3d3c371..00000000000000 --- a/selfdrive/debug/test_carcontroller.py +++ /dev/null @@ -1,92 +0,0 @@ -#!/usr/bin/env python -import time -import numpy as np -import zmq -from evdev import InputDevice -from select import select - -from cereal import car -from common.realtime import Ratekeeper - -import selfdrive.messaging as messaging -from selfdrive.services import service_list -from selfdrive.car import get_car - - -if __name__ == "__main__": - # ***** connect to joystick ***** - # we use a Mad Catz V.1 - dev = InputDevice("/dev/input/event8") - print dev - - button_values = [0]*7 - axis_values = [0.0, 0.0, 0.0] - - # ***** connect to car ***** - context = zmq.Context() - logcan = messaging.sub_sock(context, service_list['can'].port) - sendcan = messaging.pub_sock(context, service_list['sendcan'].port) - - CI, CP = get_car(logcan, sendcan) - CC = car.CarControl.new_message() - - rk = Ratekeeper(100) - - while 1: - # **** handle joystick **** - r, w, x = select([dev], [], [], 0.0) - if dev in r: - for event in dev.read(): - # button event - if event.type == 1: - btn = event.code - 288 - if btn >= 0 and btn < 7: - button_values[btn] = int(event.value) - - # axis move event - if event.type == 3: - if event.code < 3: - if event.code == 2: - axis_values[event.code] = np.clip((255-int(event.value))/250.0, 0.0, 1.0) - else: - DEADZONE = 5 - if event.value-DEADZONE < 128 and event.value+DEADZONE > 128: - event.value = 128 - axis_values[event.code] = np.clip((int(event.value)-128)/120.0, -1.0, 1.0) - - print axis_values, button_values - # **** handle car **** - - CS = CI.update(CC) - #print CS - CC = car.CarControl.new_message() - - - CC.enabled = True - - CC.gas = float(np.clip(-axis_values[1], 0, 1.0)) - CC.brake = float(np.clip(axis_values[1], 0, 1.0)) - CC.steeringTorque = float(-axis_values[0]) - - CC.hudControl.speedVisible = bool(button_values[1]) - CC.hudControl.lanesVisible = bool(button_values[2]) - CC.hudControl.leadVisible = bool(button_values[3]) - - CC.cruiseControl.override = bool(button_values[0]) - CC.cruiseControl.cancel = bool(button_values[-1]) - - CC.hudControl.setSpeed = float(axis_values[2] * 100.0) - - # TODO: test alerts - CC.hudControl.visualAlert = "none" - CC.hudControl.audibleAlert = "none" - - #print CC - - if not CI.apply(CC): - print "CONTROLS FAILED" - - rk.keep_time() - - - diff --git a/selfdrive/debug/test_carstate.py b/selfdrive/debug/test_carstate.py deleted file mode 100755 index 98d2f7fc154427..00000000000000 --- a/selfdrive/debug/test_carstate.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python -import os -import zmq -from cereal import car - -import selfdrive.messaging as messaging -from selfdrive.services import service_list - -from selfdrive.car import get_car - -def bpressed(CS, btype): - for b in CS.buttonEvents: - if b.type == btype: - return True - return False - -def test_loop(): - context = zmq.Context() - logcan = messaging.sub_sock(context, service_list['can'].port) - - CI, CP = get_car(logcan) - - state = 0 - - states = [ - "'seatbeltNotLatched' in CS.errors", - "CS.gasPressed", - "CS.brakePressed", - "CS.steeringPressed", - "bpressed(CS, 'leftBlinker')", - "bpressed(CS, 'rightBlinker')", - "bpressed(CS, 'cancel')", - "bpressed(CS, 'accelCruise')", - "bpressed(CS, 'decelCruise')", - "bpressed(CS, 'altButton1')", - "'doorOpen' in CS.errors", - "False"] - - while 1: - CC = car.CarControl.new_message() - # read CAN - CS = CI.update(CC) - - while eval(states[state]) == True: - state += 1 - - print "IN STATE %d: waiting for %s" % (state, states[state]) - #print CS - -if __name__ == "__main__": - test_loop() - diff --git a/selfdrive/locationd/__init__.py b/selfdrive/locationd/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/locationd/calibration_values.py b/selfdrive/locationd/calibration_values.py new file mode 100644 index 00000000000000..f2909007594924 --- /dev/null +++ b/selfdrive/locationd/calibration_values.py @@ -0,0 +1,11 @@ +import math + +class Filter: + MIN_SPEED = 7 # m/s (~15.5mph) + MAX_YAW_RATE = math.radians(3) # per second + +class Calibration: + UNCALIBRATED = 0 + CALIBRATED = 1 + INVALID = 2 + diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py new file mode 100755 index 00000000000000..36d76aa59e7600 --- /dev/null +++ b/selfdrive/locationd/calibrationd.py @@ -0,0 +1,253 @@ +#!/usr/bin/env python +import os +import zmq +import cv2 +import copy +import json +import numpy as np +import selfdrive.messaging as messaging +from selfdrive.locationd.calibration_values import Calibration, Filter +from selfdrive.swaglog import cloudlog +from selfdrive.services import service_list +from common.params import Params +from common.ffi_wrapper import ffi_wrap +import common.transformations.orientation as orient +from common.transformations.model import model_height, get_camera_frame_from_model_frame +from common.transformations.camera import view_frame_from_device_frame, get_view_frame_from_road_frame, \ + eon_intrinsics, get_calib_from_vp, normalize, denormalize, H, W + + +FRAMES_NEEDED = 120 # allow to update VP every so many frames +VP_CYCLES_NEEDED = 2 +CALIBRATION_CYCLES_NEEDED = FRAMES_NEEDED * VP_CYCLES_NEEDED +DT = 0.1 # nominal time step of 10Hz (orbd_live runs slower on pc) +VP_RATE_LIM = 2. * DT # 2 px/s +VP_INIT = np.array([W/2., H/2.]) +EXTERNAL_PATH = os.path.dirname(os.path.abspath(__file__)) +# big model is 864x288 +VP_VALIDITY_CORNERS = np.array([[-150., -200.], [150., 200.]]) + VP_INIT +GRID_WEIGHT_INIT = 2e6 +MAX_LINES = 500 # max lines to avoid over computation +HOOD_HEIGHT = H*3/4 # the part of image usually free from the car's hood + +DEBUG = os.getenv("DEBUG") is not None + +# Wrap c code for slow grid incrementation +c_header = "\nvoid increment_grid(double *grid, double *lines, long long n);" +c_code = "#define H %d\n" % H +c_code += "#define W %d\n" % W +c_code += "\n" + open(os.path.join(EXTERNAL_PATH, "get_vp.c")).read() +ffi, lib = ffi_wrap('get_vp', c_code, c_header) + + +def increment_grid_c(grid, lines, n): + lib.increment_grid(ffi.cast("double *", grid.ctypes.data), + ffi.cast("double *", lines.ctypes.data), + ffi.cast("long long", n)) + +def get_lines(p): + A = (p[:,0,1] - p[:,1,1]) + B = (p[:,1,0] - p[:,0,0]) + C = (p[:,0,0]*p[:,1,1] - p[:,1,0]*p[:,0,1]) + return np.column_stack((A, B, -C)) + +def correct_pts(pts, rot_speeds, dt): + pts = np.hstack((pts, np.ones((pts.shape[0],1)))) + cam_rot = dt * view_frame_from_device_frame.dot(rot_speeds) + rot = orient.rot_matrix(*cam_rot.T).T + pts_corrected = rot.dot(pts.T).T + pts_corrected[:,0] /= pts_corrected[:,2] + pts_corrected[:,1] /= pts_corrected[:,2] + return pts_corrected[:,:2] + +def gaussian_kernel(sizex, sizey, stdx, stdy, dx, dy): + y, x = np.mgrid[-sizey:sizey+1, -sizex:sizex+1] + g = np.exp(-((x - dx)**2 / (2. * stdx**2) + (y - dy)**2 / (2. * stdy**2))) + return g / g.sum() + +def gaussian_kernel_1d(kernel): + #creates separable gaussian filter + u,s,v = np.linalg.svd(kernel) + x = u[:,0]*np.sqrt(s[0]) + y = np.sqrt(s[0])*v[0,:] + return x, y + +def blur_image(img, kernel_x, kernel_y): + return cv2.sepFilter2D(img.astype(np.uint16), -1, kernel_x, kernel_y) + +def is_calibration_valid(vp): + return vp[0] > VP_VALIDITY_CORNERS[0,0] and vp[0] < VP_VALIDITY_CORNERS[1,0] and \ + vp[1] > VP_VALIDITY_CORNERS[0,1] and vp[1] < VP_VALIDITY_CORNERS[1,1] + +class Calibrator(object): + def __init__(self, param_put=False): + self.param_put = param_put + self.speed = 0 + self.vp_cycles = 0 + self.angle_offset = 0. + self.yaw_rate = 0. + self.l100_last_updated = 0 + self.prev_orbs = None + self.kernel = gaussian_kernel(11, 11, 2.35, 2.35, 0, 0) + self.kernel_x, self.kernel_y = gaussian_kernel_1d(self.kernel) + + self.vp = copy.copy(VP_INIT) + self.cal_status = Calibration.UNCALIBRATED + self.frame_counter = 0 + self.params = Params() + calibration_params = self.params.get("CalibrationParams") + if calibration_params: + try: + calibration_params = json.loads(calibration_params) + self.vp = np.array(calibration_params["vanishing_point"]) + self.cal_status = Calibration.CALIBRATED if is_calibration_valid(self.vp) else Calibration.INVALID + self.vp_cycles = VP_CYCLES_NEEDED + self.frame_counter = CALIBRATION_CYCLES_NEEDED + except Exception: + cloudlog.exception("CalibrationParams file found but error encountered") + + self.vp_unfilt = self.vp + self.orb_last_updated = 0. + self.reset_grid() + + def reset_grid(self): + if self.cal_status == Calibration.UNCALIBRATED: + # empty grid + self.grid = np.zeros((H+1, W+1), dtype=np.float) + else: + # gaussian grid, centered at vp + self.grid = gaussian_kernel(W/2., H/2., 16, 16, self.vp[0] - W/2., self.vp[1] - H/2.) * GRID_WEIGHT_INIT + + def rescale_grid(self): + self.grid *= 0.9 + + def update(self, uvs, yaw_rate, speed): + if len(uvs) < 10 or \ + abs(yaw_rate) > Filter.MAX_YAW_RATE or \ + speed < Filter.MIN_SPEED: + return + rot_speeds = np.array([0.,0.,-yaw_rate]) + uvs[:,1,:] = denormalize(correct_pts(normalize(uvs[:,1,:]), rot_speeds, self.dt)) + # exclude tracks where: + # - pixel movement was less than 10 pixels + # - tracks are in the "hood region" + good_tracks = np.all([np.linalg.norm(uvs[:,1,:] - uvs[:,0,:], axis=1) > 10, + uvs[:,0,1] < HOOD_HEIGHT, + uvs[:,1,1] < HOOD_HEIGHT], axis = 0) + uvs = uvs[good_tracks] + if uvs.shape[0] > MAX_LINES: + uvs = uvs[np.random.choice(uvs.shape[0], MAX_LINES, replace=False), :] + lines = get_lines(uvs) + + increment_grid_c(self.grid, lines, len(lines)) + self.frame_counter += 1 + if (self.frame_counter % FRAMES_NEEDED) == 0: + grid = blur_image(self.grid, self.kernel_x, self.kernel_y) + argmax_vp = np.unravel_index(np.argmax(grid), grid.shape)[::-1] + self.rescale_grid() + self.vp_unfilt = np.array(argmax_vp) + self.vp_cycles += 1 + if (self.vp_cycles - VP_CYCLES_NEEDED) % 10 == 0: # update file every 10 + # skip rate_lim before writing the file to avoid writing a lagged vp + if self.cal_status != Calibration.CALIBRATED: + self.vp = self.vp_unfilt + if self.param_put: + cal_params = {"vanishing_point": list(self.vp), "angle_offset2": self.angle_offset} + self.params.put("CalibrationParams", json.dumps(cal_params)) + return self.vp_unfilt + + def parse_orb_features(self, log): + matches = np.array(log.orbFeatures.matches) + n = len(log.orbFeatures.matches) + t = float(log.orbFeatures.timestampLastEof)*1e-9 + if t == 0 or n == 0: + return t, np.zeros((0,2,2)) + orbs = denormalize(np.column_stack((log.orbFeatures.xs, + log.orbFeatures.ys))) + if self.prev_orbs is not None: + valid_matches = (matches > -1) & (matches < len(self.prev_orbs)) + tracks = np.hstack((orbs[valid_matches], self.prev_orbs[matches[valid_matches]])).reshape((-1,2,2)) + else: + tracks = np.zeros((0,2,2)) + self.prev_orbs = orbs + return t, tracks + + def update_vp(self): + # rate limit to not move VP too fast + self.vp = np.clip(self.vp_unfilt, self.vp - VP_RATE_LIM, self.vp + VP_RATE_LIM) + if self.vp_cycles < VP_CYCLES_NEEDED: + self.cal_status = Calibration.UNCALIBRATED + else: + self.cal_status = Calibration.CALIBRATED if is_calibration_valid(self.vp) else Calibration.INVALID + + def handle_orb_features(self, log): + self.update_vp() + self.time_orb, frame_raw = self.parse_orb_features(log) + self.dt = min(self.time_orb - self.orb_last_updated, 1.) + self.orb_last_updated = self.time_orb + if self.time_orb - self.l100_last_updated < 1: + return self.update(frame_raw, self.yaw_rate, self.speed) + + def handle_live100(self, log): + self.l100_last_updated = self.time_orb + self.speed = log.live100.vEgo + self.angle_offset = log.live100.angleOffset + self.yaw_rate = log.live100.curvature * self.speed + + def handle_debug(self): + grid_blurred = blur_image(self.grid, self.kernel_x, self.kernel_y) + grid_grey = np.clip(grid_blurred/(0.1 + np.max(grid_blurred))*255, 0, 255) + grid_color = np.repeat(grid_grey[:,:,np.newaxis], 3, axis=2) + grid_color[:,:,0] = 0 + cv2.circle(grid_color, tuple(self.vp.astype(np.int64)), 2, (255, 255, 0), -1) + cv2.imshow("debug", grid_color.astype(np.uint8)) + + cv2.waitKey(1) + + def send_data(self, livecalibration): + calib = get_calib_from_vp(self.vp) + extrinsic_matrix = get_view_frame_from_road_frame(0, calib[1], calib[2], model_height) + ke = eon_intrinsics.dot(extrinsic_matrix) + warp_matrix = get_camera_frame_from_model_frame(ke, model_height) + + cal_send = messaging.new_message() + cal_send.init('liveCalibration') + cal_send.liveCalibration.calStatus = self.cal_status + cal_send.liveCalibration.calPerc = min(self.frame_counter * 100 / CALIBRATION_CYCLES_NEEDED, 100) + cal_send.liveCalibration.warpMatrix2 = map(float, warp_matrix.flatten()) + cal_send.liveCalibration.extrinsicMatrix = map(float, extrinsic_matrix.flatten()) + + livecalibration.send(cal_send.to_bytes()) + + +def calibrationd_thread(gctx=None, addr="127.0.0.1"): + context = zmq.Context() + + live100 = messaging.sub_sock(context, service_list['live100'].port, addr=addr, conflate=True) + orbfeatures = messaging.sub_sock(context, service_list['orbFeatures'].port, addr=addr, conflate=True) + livecalibration = messaging.pub_sock(context, service_list['liveCalibration'].port) + + calibrator = Calibrator(param_put = True) + + # buffer with all the messages that still need to be input into the kalman + while 1: + of = messaging.recv_one(orbfeatures) + l100 = messaging.recv_one_or_none(live100) + + new_vp = calibrator.handle_orb_features(of) + if DEBUG and new_vp is not None: + print 'got new vp', new_vp + if l100 is not None: + calibrator.handle_live100(l100) + if DEBUG: + calibrator.handle_debug() + + calibrator.send_data(livecalibration) + + +def main(gctx=None, addr="127.0.0.1"): + calibrationd_thread(gctx, addr) + +if __name__ == "__main__": + main() + diff --git a/selfdrive/locationd/ephemeris.py b/selfdrive/locationd/ephemeris.py new file mode 100644 index 00000000000000..dd8155e19a4507 --- /dev/null +++ b/selfdrive/locationd/ephemeris.py @@ -0,0 +1,137 @@ +def GET_FIELD_U(w, nb, pos): + return (((w) >> (pos)) & ((1 << (nb)) - 1)) + + +def twos_complement(v, nb): + sign = v >> (nb - 1) + value = v + if sign != 0: + value = value - (1 << nb) + return value + + +def GET_FIELD_S(w, nb, pos): + v = GET_FIELD_U(w, nb, pos) + return twos_complement(v, nb) + + +def extract_uint8(v, b): + return (v >> (8 * (3 - b))) & 255 + +def extract_int8(v, b): + value = extract_uint8(v, b) + if value > 127: + value -= 256 + return value + +class EphemerisData: + '''container for parsing a AID_EPH message + Thanks to Sylvain Munaut + http://cgit.osmocom.org/cgit/osmocom-lcs/tree/gps.c +on of this parser + + See IS-GPS-200F.pdf Table 20-III for the field meanings, scaling factors and + field widths + ''' + + def __init__(self, svId, subframes): + from math import pow + self.svId = svId + week_no = GET_FIELD_U(subframes[1][2+0], 10, 20) + # code_on_l2 = GET_FIELD_U(subframes[1][0], 2, 12) + # sv_ura = GET_FIELD_U(subframes[1][0], 4, 8) + # sv_health = GET_FIELD_U(subframes[1][0], 6, 2) + # l2_p_flag = GET_FIELD_U(subframes[1][1], 1, 23) + t_gd = GET_FIELD_S(subframes[1][2+4], 8, 6) + iodc = (GET_FIELD_U(subframes[1][2+0], 2, 6) << 8) | GET_FIELD_U( + subframes[1][2+5], 8, 22) + + t_oc = GET_FIELD_U(subframes[1][2+5], 16, 6) + a_f2 = GET_FIELD_S(subframes[1][2+6], 8, 22) + a_f1 = GET_FIELD_S(subframes[1][2+6], 16, 6) + a_f0 = GET_FIELD_S(subframes[1][2+7], 22, 8) + + c_rs = GET_FIELD_S(subframes[2][2+0], 16, 6) + delta_n = GET_FIELD_S(subframes[2][2+1], 16, 14) + m_0 = (GET_FIELD_S(subframes[2][2+1], 8, 6) << 24) | GET_FIELD_U( + subframes[2][2+2], 24, 6) + c_uc = GET_FIELD_S(subframes[2][2+3], 16, 14) + e = (GET_FIELD_U(subframes[2][2+3], 8, 6) << 24) | GET_FIELD_U(subframes[2][2+4], 24, 6) + c_us = GET_FIELD_S(subframes[2][2+5], 16, 14) + a_powhalf = (GET_FIELD_U(subframes[2][2+5], 8, 6) << 24) | GET_FIELD_U( + subframes[2][2+6], 24, 6) + t_oe = GET_FIELD_U(subframes[2][2+7], 16, 14) + # fit_flag = GET_FIELD_U(subframes[2][7], 1, 7) + + c_ic = GET_FIELD_S(subframes[3][2+0], 16, 14) + omega_0 = (GET_FIELD_S(subframes[3][2+0], 8, 6) << 24) | GET_FIELD_U( + subframes[3][2+1], 24, 6) + c_is = GET_FIELD_S(subframes[3][2+2], 16, 14) + i_0 = (GET_FIELD_S(subframes[3][2+2], 8, 6) << 24) | GET_FIELD_U( + subframes[3][2+3], 24, 6) + c_rc = GET_FIELD_S(subframes[3][2+4], 16, 14) + w = (GET_FIELD_S(subframes[3][2+4], 8, 6) << 24) | GET_FIELD_U(subframes[3][5], 24, 6) + omega_dot = GET_FIELD_S(subframes[3][2+6], 24, 6) + idot = GET_FIELD_S(subframes[3][2+7], 14, 8) + + self._rsvd1 = GET_FIELD_U(subframes[1][2+1], 23, 6) + self._rsvd2 = GET_FIELD_U(subframes[1][2+2], 24, 6) + self._rsvd3 = GET_FIELD_U(subframes[1][2+3], 24, 6) + self._rsvd4 = GET_FIELD_U(subframes[1][2+4], 16, 14) + self.aodo = GET_FIELD_U(subframes[2][2+7], 5, 8) + + # Definition of Pi used in the GPS coordinate system + gpsPi = 3.1415926535898 + + # now form variables in radians, meters and seconds etc + self.Tgd = t_gd * pow(2, -31) + self.A = pow(a_powhalf * pow(2, -19), 2.0) + self.cic = c_ic * pow(2, -29) + self.cis = c_is * pow(2, -29) + self.crc = c_rc * pow(2, -5) + self.crs = c_rs * pow(2, -5) + self.cuc = c_uc * pow(2, -29) + self.cus = c_us * pow(2, -29) + self.deltaN = delta_n * pow(2, -43) * gpsPi + self.ecc = e * pow(2, -33) + self.i0 = i_0 * pow(2, -31) * gpsPi + self.idot = idot * pow(2, -43) * gpsPi + self.M0 = m_0 * pow(2, -31) * gpsPi + self.omega = w * pow(2, -31) * gpsPi + self.omega_dot = omega_dot * pow(2, -43) * gpsPi + self.omega0 = omega_0 * pow(2, -31) * gpsPi + self.toe = t_oe * pow(2, 4) + + # clock correction information + self.toc = t_oc * pow(2, 4) + self.gpsWeek = week_no + self.af0 = a_f0 * pow(2, -31) + self.af1 = a_f1 * pow(2, -43) + self.af2 = a_f2 * pow(2, -55) + + iode1 = GET_FIELD_U(subframes[2][2+0], 8, 22) + iode2 = GET_FIELD_U(subframes[3][2+7], 8, 22) + self.valid = (iode1 == iode2) and (iode1 == (iodc & 0xff)) + self.iode = iode1 + + if GET_FIELD_U(subframes[4][2+0], 6, 22) == 56 and \ + GET_FIELD_U(subframes[4][2+0], 2, 28) == 1 and \ + GET_FIELD_U(subframes[5][2+0], 2, 28) == 1: + a0 = GET_FIELD_S(subframes[4][2], 8, 14) * pow(2, -30) + a1 = GET_FIELD_S(subframes[4][2], 8, 6) * pow(2, -27) + a2 = GET_FIELD_S(subframes[4][3], 8, 22) * pow(2, -24) + a3 = GET_FIELD_S(subframes[4][3], 8, 14) * pow(2, -24) + b0 = GET_FIELD_S(subframes[4][3], 8, 6) * pow(2, 11) + b1 = GET_FIELD_S(subframes[4][4], 8, 22) * pow(2, 14) + b2 = GET_FIELD_S(subframes[4][4], 8, 14) * pow(2, 16) + b3 = GET_FIELD_S(subframes[4][4], 8, 6) * pow(2, 16) + + self.ionoAlpha = [a0, a1, a2, a3] + self.ionoBeta = [b0, b1, b2, b3] + self.ionoCoeffsValid = True + else: + self.ionoAlpha = [] + self.ionoBeta = [] + self.ionoCoeffsValid = False + + diff --git a/selfdrive/locationd/get_vp.c b/selfdrive/locationd/get_vp.c new file mode 100644 index 00000000000000..8a48c88150b4cb --- /dev/null +++ b/selfdrive/locationd/get_vp.c @@ -0,0 +1,41 @@ +int get_intersections(double *lines, double *intersections, long long n) { + double D, Dx, Dy; + double x, y; + double *L1, *L2; + int k = 0; + for (int i=0; i < n; i++) { + for (int j=0; j < n; j++) { + L1 = lines + i*3; + L2 = lines + j*3; + D = L1[0] * L2[1] - L1[1] * L2[0]; + Dx = L1[2] * L2[1] - L1[1] * L2[2]; + Dy = L1[0] * L2[2] - L1[2] * L2[0]; + // only intersect lines from different quadrants and only left-right crossing + if ((D != 0) && (L1[0]*L2[0]*L1[1]*L2[1] < 0) && (L1[1]*L2[1] < 0)){ + x = Dx / D; + y = Dy / D; + if ((0 < x) && + (x < W) && + (0 < y) && + (y < H)){ + intersections[k*2 + 0] = x; + intersections[k*2 + 1] = y; + k++; + } + } + } + } + return k; +} + +void increment_grid(double *grid, double *lines, long long n) { + double *intersections = (double*) malloc(n*n*2*sizeof(double)); + int y, x, k; + k = get_intersections(lines, intersections, n); + for (int i=0; i < k; i++) { + x = (int) (intersections[i*2 + 0] + 0.5); + y = (int) (intersections[i*2 + 1] + 0.5); + grid[y*(W+1) + x] += 1.; + } + free(intersections); +} diff --git a/selfdrive/locationd/ublox.py b/selfdrive/locationd/ublox.py new file mode 100644 index 00000000000000..228dfc8433e9c1 --- /dev/null +++ b/selfdrive/locationd/ublox.py @@ -0,0 +1,995 @@ +#!/usr/bin/env python +''' +UBlox binary protocol handling + +Copyright Andrew Tridgell, October 2012 +Released under GNU GPL version 3 or later + +WARNING: This code has originally intended for +ublox version 7, it has been adapted to work +for ublox version 8, not all functions may work. +''' + +import struct +import time, os + +# protocol constants +PREAMBLE1 = 0xb5 +PREAMBLE2 = 0x62 + +# message classes +CLASS_NAV = 0x01 +CLASS_RXM = 0x02 +CLASS_INF = 0x04 +CLASS_ACK = 0x05 +CLASS_CFG = 0x06 +CLASS_MON = 0x0A +CLASS_AID = 0x0B +CLASS_TIM = 0x0D +CLASS_ESF = 0x10 + +# ACK messages +MSG_ACK_NACK = 0x00 +MSG_ACK_ACK = 0x01 + +# NAV messages +MSG_NAV_POSECEF = 0x1 +MSG_NAV_POSLLH = 0x2 +MSG_NAV_STATUS = 0x3 +MSG_NAV_DOP = 0x4 +MSG_NAV_SOL = 0x6 +MSG_NAV_PVT = 0x7 +MSG_NAV_POSUTM = 0x8 +MSG_NAV_VELNED = 0x12 +MSG_NAV_VELECEF = 0x11 +MSG_NAV_TIMEGPS = 0x20 +MSG_NAV_TIMEUTC = 0x21 +MSG_NAV_CLOCK = 0x22 +MSG_NAV_SVINFO = 0x30 +MSG_NAV_AOPSTATUS = 0x60 +MSG_NAV_DGPS = 0x31 +MSG_NAV_DOP = 0x04 +MSG_NAV_EKFSTATUS = 0x40 +MSG_NAV_SBAS = 0x32 +MSG_NAV_SOL = 0x06 + +# RXM messages +MSG_RXM_RAW = 0x15 +MSG_RXM_SFRB = 0x11 +MSG_RXM_SFRBX = 0x13 +MSG_RXM_SVSI = 0x20 +MSG_RXM_EPH = 0x31 +MSG_RXM_ALM = 0x30 +MSG_RXM_PMREQ = 0x41 + +# AID messages +MSG_AID_ALM = 0x30 +MSG_AID_EPH = 0x31 +MSG_AID_ALPSRV = 0x32 +MSG_AID_AOP = 0x33 +MSG_AID_DATA = 0x10 +MSG_AID_ALP = 0x50 +MSG_AID_DATA = 0x10 +MSG_AID_HUI = 0x02 +MSG_AID_INI = 0x01 +MSG_AID_REQ = 0x00 + +# CFG messages +MSG_CFG_PRT = 0x00 +MSG_CFG_ANT = 0x13 +MSG_CFG_DAT = 0x06 +MSG_CFG_EKF = 0x12 +MSG_CFG_ESFGWT = 0x29 +MSG_CFG_CFG = 0x09 +MSG_CFG_USB = 0x1b +MSG_CFG_RATE = 0x08 +MSG_CFG_SET_RATE = 0x01 +MSG_CFG_NAV5 = 0x24 +MSG_CFG_FXN = 0x0E +MSG_CFG_INF = 0x02 +MSG_CFG_ITFM = 0x39 +MSG_CFG_MSG = 0x01 +MSG_CFG_NAVX5 = 0x23 +MSG_CFG_NMEA = 0x17 +MSG_CFG_NVS = 0x22 +MSG_CFG_PM2 = 0x3B +MSG_CFG_PM = 0x32 +MSG_CFG_RINV = 0x34 +MSG_CFG_RST = 0x04 +MSG_CFG_RXM = 0x11 +MSG_CFG_SBAS = 0x16 +MSG_CFG_TMODE2 = 0x3D +MSG_CFG_TMODE = 0x1D +MSG_CFG_TPS = 0x31 +MSG_CFG_TP = 0x07 +MSG_CFG_GNSS = 0x3E +MSG_CFG_ODO = 0x1E + +# ESF messages +MSG_ESF_MEAS = 0x02 +MSG_ESF_STATUS = 0x10 + +# INF messages +MSG_INF_DEBUG = 0x04 +MSG_INF_ERROR = 0x00 +MSG_INF_NOTICE = 0x02 +MSG_INF_TEST = 0x03 +MSG_INF_WARNING = 0x01 + +# MON messages +MSG_MON_SCHD = 0x01 +MSG_MON_HW = 0x09 +MSG_MON_HW2 = 0x0B +MSG_MON_IO = 0x02 +MSG_MON_MSGPP = 0x06 +MSG_MON_RXBUF = 0x07 +MSG_MON_RXR = 0x21 +MSG_MON_TXBUF = 0x08 +MSG_MON_VER = 0x04 + +# TIM messages +MSG_TIM_TP = 0x01 +MSG_TIM_TM2 = 0x03 +MSG_TIM_SVIN = 0x04 +MSG_TIM_VRFY = 0x06 + +# port IDs +PORT_DDC = 0 +PORT_SERIAL1 = 1 +PORT_SERIAL2 = 2 +PORT_USB = 3 +PORT_SPI = 4 + +# dynamic models +DYNAMIC_MODEL_PORTABLE = 0 +DYNAMIC_MODEL_STATIONARY = 2 +DYNAMIC_MODEL_PEDESTRIAN = 3 +DYNAMIC_MODEL_AUTOMOTIVE = 4 +DYNAMIC_MODEL_SEA = 5 +DYNAMIC_MODEL_AIRBORNE1G = 6 +DYNAMIC_MODEL_AIRBORNE2G = 7 +DYNAMIC_MODEL_AIRBORNE4G = 8 + +#reset items +RESET_HOT = 0 +RESET_WARM = 1 +RESET_COLD = 0xFFFF + +RESET_HW = 0 +RESET_SW = 1 +RESET_SW_GPS = 2 +RESET_HW_GRACEFUL = 4 +RESET_GPS_STOP = 8 +RESET_GPS_START = 9 + + +class UBloxError(Exception): + '''Ublox error class''' + + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + + +class UBloxAttrDict(dict): + '''allow dictionary members as attributes''' + + def __init__(self): + dict.__init__(self) + + def __getattr__(self, name): + try: + return self.__getitem__(name) + except KeyError: + raise AttributeError(name) + + def __setattr__(self, name, value): + if self.__dict__.has_key(name): + # allow set on normal attributes + dict.__setattr__(self, name, value) + else: + self.__setitem__(name, value) + + +def ArrayParse(field): + '''parse an array descriptor''' + arridx = field.find('[') + if arridx == -1: + return (field, -1) + alen = int(field[arridx + 1:-1]) + fieldname = field[:arridx] + return (fieldname, alen) + + +class UBloxDescriptor: + '''class used to describe the layout of a UBlox message''' + + def __init__(self, + name, + msg_format, + fields=[], + count_field=None, + format2=None, + fields2=None): + self.name = name + self.msg_format = msg_format + self.fields = fields + self.count_field = count_field + self.format2 = format2 + self.fields2 = fields2 + + def unpack(self, msg): + '''unpack a UBloxMessage, creating the .fields and ._recs attributes in msg''' + msg._fields = {} + + # unpack main message blocks. A comm + formats = self.msg_format.split(',') + buf = msg._buf[6:-2] + count = 0 + msg._recs = [] + fields = self.fields[:] + + for fmt in formats: + size1 = struct.calcsize(fmt) + if size1 > len(buf): + raise UBloxError("%s INVALID_SIZE1=%u" % (self.name, len(buf))) + f1 = list(struct.unpack(fmt, buf[:size1])) + i = 0 + while i < len(f1): + field = fields.pop(0) + (fieldname, alen) = ArrayParse(field) + if alen == -1: + msg._fields[fieldname] = f1[i] + if self.count_field == fieldname: + count = int(f1[i]) + i += 1 + else: + msg._fields[fieldname] = [0] * alen + for a in range(alen): + msg._fields[fieldname][a] = f1[i] + i += 1 + buf = buf[size1:] + if len(buf) == 0: + break + + if self.count_field == '_remaining': + count = len(buf) / struct.calcsize(self.format2) + + if count == 0: + msg._unpacked = True + if len(buf) != 0: + raise UBloxError("EXTRA_BYTES=%u" % len(buf)) + return + + size2 = struct.calcsize(self.format2) + for c in range(count): + r = UBloxAttrDict() + if size2 > len(buf): + raise UBloxError("INVALID_SIZE=%u, " % len(buf)) + f2 = list(struct.unpack(self.format2, buf[:size2])) + for i in range(len(self.fields2)): + r[self.fields2[i]] = f2[i] + buf = buf[size2:] + msg._recs.append(r) + if len(buf) != 0: + raise UBloxError("EXTRA_BYTES=%u" % len(buf)) + msg._unpacked = True + + def pack(self, msg, msg_class=None, msg_id=None): + '''pack a UBloxMessage from the .fields and ._recs attributes in msg''' + f1 = [] + if msg_class is None: + msg_class = msg.msg_class() + if msg_id is None: + msg_id = msg.msg_id() + msg._buf = '' + + fields = self.fields[:] + for f in fields: + (fieldname, alen) = ArrayParse(f) + if not fieldname in msg._fields: + break + if alen == -1: + f1.append(msg._fields[fieldname]) + else: + for a in range(alen): + f1.append(msg._fields[fieldname][a]) + try: + # try full length message + fmt = self.msg_format.replace(',', '') + msg._buf = struct.pack(fmt, *tuple(f1)) + except Exception: + # try without optional part + fmt = self.msg_format.split(',')[0] + msg._buf = struct.pack(fmt, *tuple(f1)) + + length = len(msg._buf) + if msg._recs: + length += len(msg._recs) * struct.calcsize(self.format2) + header = struct.pack('= level: + print(msg) + + def unpack(self): + '''unpack a message''' + if not self.valid(): + raise UBloxError('INVALID MESSAGE') + type = self.msg_type() + if not type in msg_types: + raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) + msg_types[type].unpack(self) + return self._fields, self._recs + + def pack(self): + '''pack a message''' + if not self.valid(): + raise UBloxError('INVALID MESSAGE') + type = self.msg_type() + if not type in msg_types: + raise UBloxError('Unknown message %s' % str(type)) + msg_types[type].pack(self) + + def name(self): + '''return the short string name for a message''' + if not self.valid(): + raise UBloxError('INVALID MESSAGE') + type = self.msg_type() + if not type in msg_types: + raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) + return msg_types[type].name + + def msg_class(self): + '''return the message class''' + return ord(self._buf[2]) + + def msg_id(self): + '''return the message id within the class''' + return ord(self._buf[3]) + + def msg_type(self): + '''return the message type tuple (class, id)''' + return (self.msg_class(), self.msg_id()) + + def msg_length(self): + '''return the payload length''' + (payload_length, ) = struct.unpack(' 0 and ord(self._buf[0]) != PREAMBLE1: + return False + if len(self._buf) > 1 and ord(self._buf[1]) != PREAMBLE2: + self.debug(1, "bad pre2") + return False + if self.needed_bytes() == 0 and not self.valid(): + if len(self._buf) > 8: + self.debug(1, "bad checksum len=%u needed=%u" % (len(self._buf), + self.needed_bytes())) + else: + self.debug(1, "bad len len=%u needed=%u" % (len(self._buf), self.needed_bytes())) + return False + return True + + def add(self, bytes): + '''add some bytes to a message''' + self._buf += bytes + while not self.valid_so_far() and len(self._buf) > 0: + '''handle corrupted streams''' + self._buf = self._buf[1:] + if self.needed_bytes() < 0: + self._buf = "" + + def checksum(self, data=None): + '''return a checksum tuple for a message''' + if data is None: + data = self._buf[2:-2] + #cs = 0 + ck_a = 0 + ck_b = 0 + for i in data: + ck_a = (ck_a + ord(i)) & 0xFF + ck_b = (ck_b + ck_a) & 0xFF + return (ck_a, ck_b) + + def valid_checksum(self): + '''check if the checksum is OK''' + (ck_a, ck_b) = self.checksum() + #d = self._buf[2:-2] + (ck_a2, ck_b2) = struct.unpack('= 8 and self.needed_bytes() == 0 and self.valid_checksum() + + +class UBlox: + '''main UBlox control class. + + port can be a file (for reading only) or a serial device + ''' + + def __init__(self, port, baudrate=115200, timeout=0, panda=False, grey=False): + + self.serial_device = port + self.baudrate = baudrate + self.use_sendrecv = False + self.read_only = False + self.debug_level = 0 + + if panda: + from panda import Panda, PandaSerial + + self.panda = Panda() + + # resetting U-Blox module + self.panda.set_esp_power(0) + time.sleep(0.1) + self.panda.set_esp_power(1) + time.sleep(0.5) + + # can't set above 9600 now... + self.baudrate = 9600 + self.dev = PandaSerial(self.panda, 1, self.baudrate) + + self.baudrate = 460800 + print "upping baud:",self.baudrate + self.send_nmea("$PUBX,41,1,0007,0003,%u,0" % self.baudrate) + time.sleep(0.1) + + self.dev = PandaSerial(self.panda, 1, self.baudrate) + elif grey: + import zmq + from selfdrive.services import service_list + import selfdrive.messaging as messaging + + class BoarddSerial(object): + def __init__(self): + context = zmq.Context() + self.ubloxRaw = messaging.sub_sock(context, service_list['ubloxRaw'].port) + self.buf = "" + + def read(self, n): + for msg in messaging.drain_sock(self.ubloxRaw, len(self.buf) < n): + self.buf += msg.ubloxRaw + ret = self.buf[:n] + self.buf = self.buf[n:] + return ret + + + def write(self, dat): + pass + + self.dev = BoarddSerial() + else: + if self.serial_device.startswith("tcp:"): + import socket + a = self.serial_device.split(':') + destination_addr = (a[1], int(a[2])) + self.dev = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self.dev.connect(destination_addr) + self.dev.setblocking(1) + self.dev.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1) + self.use_sendrecv = True + elif os.path.isfile(self.serial_device): + self.read_only = True + self.dev = open(self.serial_device, mode='rb') + else: + import serial + self.dev = serial.Serial( + self.serial_device, + baudrate=self.baudrate, + dsrdtr=False, + rtscts=False, + xonxoff=False, + timeout=timeout) + + self.logfile = None + self.log = None + self.preferred_dynamic_model = None + self.preferred_usePPP = None + self.preferred_dgps_timeout = None + + def close(self): + '''close the device''' + self.dev.close() + self.dev = None + + def set_debug(self, debug_level): + '''set debug level''' + self.debug_level = debug_level + + def debug(self, level, msg): + '''write a debug message''' + if self.debug_level >= level: + print(msg) + + def set_logfile(self, logfile, append=False): + '''setup logging to a file''' + if self.log is not None: + self.log.close() + self.log = None + self.logfile = logfile + if self.logfile is not None: + if append: + mode = 'ab' + else: + mode = 'wb' + self.log = open(self.logfile, mode=mode) + + def set_preferred_dynamic_model(self, model): + '''set the preferred dynamic model for receiver''' + self.preferred_dynamic_model = model + if model is not None: + self.configure_poll(CLASS_CFG, MSG_CFG_NAV5) + + def set_preferred_dgps_timeout(self, timeout): + '''set the preferred DGPS timeout for receiver''' + self.preferred_dgps_timeout = timeout + if timeout is not None: + self.configure_poll(CLASS_CFG, MSG_CFG_NAV5) + + def set_preferred_usePPP(self, usePPP): + '''set the preferred usePPP setting for the receiver''' + if usePPP is None: + self.preferred_usePPP = None + return + self.preferred_usePPP = int(usePPP) + self.configure_poll(CLASS_CFG, MSG_CFG_NAVX5) + + def nmea_checksum(self, msg): + d = msg[1:] + cs = 0 + for i in d: + cs ^= ord(i) + return cs + + def write(self, buf): + '''write some bytes''' + if not self.read_only: + if self.use_sendrecv: + return self.dev.send(buf) + return self.dev.write(buf) + + def read(self, n): + '''read some bytes''' + if self.use_sendrecv: + import socket + try: + return self.dev.recv(n) + except socket.error: + return '' + return self.dev.read(n) + + def send_nmea(self, msg): + if not self.read_only: + s = msg + "*%02X" % self.nmea_checksum(msg) + "\r\n" + self.write(s) + + def set_binary(self): + '''put a UBlox into binary mode using a NMEA string''' + if not self.read_only: + print("try set binary at %u" % self.baudrate) + self.send_nmea("$PUBX,41,0,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,1,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,2,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,3,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,4,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,5,0007,0001,%u,0" % self.baudrate) + + def disable_nmea(self): + ''' stop sending all types of nmea messages ''' + self.send_nmea("$PUBX,40,GSV,1,1,1,1,1,0") + self.send_nmea("$PUBX,40,GGA,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,GSA,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,VTG,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,TXT,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,RMC,0,0,0,0,0,0") + + def seek_percent(self, pct): + '''seek to the given percentage of a file''' + self.dev.seek(0, 2) + filesize = self.dev.tell() + self.dev.seek(pct * 0.01 * filesize) + + def special_handling(self, msg): + '''handle automatic configuration changes''' + if msg.name() == 'CFG_NAV5': + msg.unpack() + sendit = False + pollit = False + if self.preferred_dynamic_model is not None and msg.dynModel != self.preferred_dynamic_model: + msg.dynModel = self.preferred_dynamic_model + sendit = True + pollit = True + if self.preferred_dgps_timeout is not None and msg.dgpsTimeOut != self.preferred_dgps_timeout: + msg.dgpsTimeOut = self.preferred_dgps_timeout + self.debug(2, "Setting dgpsTimeOut=%u" % msg.dgpsTimeOut) + sendit = True + # we don't re-poll for this one, as some receivers refuse to set it + if sendit: + msg.pack() + self.send(msg) + if pollit: + self.configure_poll(CLASS_CFG, MSG_CFG_NAV5) + if msg.name() == 'CFG_NAVX5' and self.preferred_usePPP is not None: + msg.unpack() + if msg.usePPP != self.preferred_usePPP: + msg.usePPP = self.preferred_usePPP + msg.mask = 1 << 13 + msg.pack() + self.send(msg) + self.configure_poll(CLASS_CFG, MSG_CFG_NAVX5) + + def receive_message(self, ignore_eof=False): + '''blocking receive of one ublox message''' + msg = UBloxMessage() + while True: + n = msg.needed_bytes() + b = self.read(n) + if not b: + if ignore_eof: + time.sleep(0.01) + continue + if len(msg._buf) > 0: + self.debug(1, "dropping %d bytes" % len(msg._buf)) + return None + msg.add(b) + if self.log is not None: + self.log.write(b) + self.log.flush() + if msg.valid(): + self.special_handling(msg) + return msg + + def receive_message_noerror(self, ignore_eof=False): + '''blocking receive of one ublox message, ignoring errors''' + try: + return self.receive_message(ignore_eof=ignore_eof) + except UBloxError as e: + print(e) + return None + except OSError as e: + # Occasionally we get hit with 'resource temporarily unavailable' + # messages here on the serial device, catch them too. + print(e) + return None + + def send(self, msg): + '''send a preformatted ublox message''' + if not msg.valid(): + self.debug(1, "invalid send") + return + if not self.read_only: + self.write(msg._buf) + + def send_message(self, msg_class, msg_id, payload): + '''send a ublox message with class, id and payload''' + msg = UBloxMessage() + msg._buf = struct.pack(' /sys/module/dwc3_msm/parameters/otg_switch") - - bus = SMBus(7, force=True) - bus.write_byte_data(0x21, 0x10, 0xf) # mask all interrupts - bus.write_byte_data(0x21, 0x03, 0x1) # set drive current and global interrupt disable - bus.write_byte_data(0x21, 0x02, 0x2) # needed? - bus.write_byte_data(0x21, 0x04, 0x4) # manual override source - bus.close() - -last_eon_fan_val = None -def set_eon_fan(val): - global last_eon_fan_val - - if not EON: - return - - if last_eon_fan_val is None or last_eon_fan_val != val: - bus = SMBus(7, force=True) - bus.write_byte_data(0x21, 0x04, 0x2) - bus.write_byte_data(0x21, 0x03, (val*2)+1) - bus.write_byte_data(0x21, 0x04, 0x4) - bus.close() - last_eon_fan_val = val - - -# temp thresholds to control fan speed - high hysteresis -_TEMP_THRS_H = [50., 65., 80., 10000] -# temp thresholds to control fan speed - low hysteresis -_TEMP_THRS_L = [42.5, 57.5, 72.5, 10000] -# fan speed options -_FAN_SPEEDS = [0, 16384, 32768, 65535] -# max fan speed only allowed if battery if hot -_BAT_TEMP_THERSHOLD = 45. - -def handle_fan(max_temp, bat_temp, fan_speed): - new_speed_h = next(speed for speed, temp_h in zip(_FAN_SPEEDS, _TEMP_THRS_H) if temp_h > max_temp) - new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_temp) - - if new_speed_h > fan_speed: - # update speed if using the high thresholds results in fan speed increment - fan_speed = new_speed_h - elif new_speed_l < fan_speed: - # update speed if using the low thresholds results in fan speed decrement - fan_speed = new_speed_l - - if bat_temp < _BAT_TEMP_THERSHOLD: - # no max fan speed unless battery is hot - fan_speed = min(fan_speed, _FAN_SPEEDS[-2]) - - set_eon_fan(fan_speed/16384) - - return fan_speed - -class LocationStarter(object): - def __init__(self): - self.last_good_loc = 0 - def update(self, started_ts, location): - rt = sec_since_boot() - - if location is None or location.accuracy > 50 or location.speed < 2: - # bad location, stop if we havent gotten a location in a while - # dont stop if we're been going for less than a minute - if started_ts: - if rt-self.last_good_loc > 60. and rt-started_ts > 60: - cloudlog.event("location_stop", - ts=rt, - started_ts=started_ts, - last_good_loc=self.last_good_loc, - location=location.to_dict() if location else None) - return False - else: - return True - else: - return False - - self.last_good_loc = rt - - if started_ts: - return True - else: - cloudlog.event("location_start", location=location.to_dict() if location else None) - return location.speed*3.6 > 10 def manager_thread(): # now loop context = zmq.Context() - thermal_sock = messaging.pub_sock(context, service_list['thermal'].port) - health_sock = messaging.sub_sock(context, service_list['health'].port) - location_sock = messaging.sub_sock(context, service_list['gpsLocation'].port) + thermal_sock = messaging.sub_sock(context, service_list['thermal'].port) cloudlog.info("manager start") cloudlog.info({"environ": os.environ}) + # save boot log + subprocess.call(["./loggerd", "--bootlog"], cwd=os.path.join(BASEDIR, "selfdrive/loggerd")) + for p in persistent_processes: start_managed_process(p) # start frame + pm_apply_packages('enable') system("am start -n ai.comma.plus.frame/.MainActivity") - # do this before panda flashing - setup_eon_fan() - if os.getenv("NOBOARD") is None: start_managed_process("pandad") params = Params() - - passive = params.get("Passive") == "1" - passive_starter = LocationStarter() - - started_ts = None logger_dead = False - count = 0 - fan_speed = 0 - ignition_seen = False - battery_was_high = False - - health_sock.RCVTIMEO = 1500 while 1: # get health of board, log this in "thermal" - td = messaging.recv_sock(health_sock, wait=True) - location = messaging.recv_sock(location_sock) - - location = location.gpsLocation if location else None - - print td - - # replace thermald - msg = read_thermal() - - # loggerd is gated based on free space - statvfs = os.statvfs(ROOT) - avail = (statvfs.f_bavail * 1.0)/statvfs.f_blocks - - # thermal message now also includes free space - msg.thermal.freeSpace = avail - with open("/sys/class/power_supply/battery/capacity") as f: - msg.thermal.batteryPercent = int(f.read()) - with open("/sys/class/power_supply/battery/status") as f: - msg.thermal.batteryStatus = f.read().strip() - with open("/sys/class/power_supply/usb/online") as f: - msg.thermal.usbOnline = bool(int(f.read())) - - # TODO: add car battery voltage check - max_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, - msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 - bat_temp = msg.thermal.bat/1000. - fan_speed = handle_fan(max_temp, bat_temp, fan_speed) - msg.thermal.fanSpeed = fan_speed - - msg.thermal.started = started_ts is not None - msg.thermal.startedTs = int(1e9*(started_ts or 0)) - - thermal_sock.send(msg.to_bytes()) - print msg + msg = messaging.recv_sock(thermal_sock, wait=True) # uploader is gated based on the phone temperature - if max_temp > 85.0: - cloudlog.warning("over temp: %r", max_temp) + if msg.thermal.thermalStatus >= ThermalStatus.yellow: kill_managed_process("uploader") - elif max_temp < 70.0: + else: start_managed_process("uploader") - if avail < 0.05: + if msg.thermal.freeSpace < 0.05: logger_dead = True - # start constellation of processes when the car starts - ignition = td is not None and td.health.started - ignition_seen = ignition_seen or ignition - - do_uninstall = params.get("DoUninstall") == "1" - accepted_terms = params.get("HasAcceptedTerms") == "1" - - should_start = ignition - - # start on gps in passive mode - if passive and not ignition_seen: - should_start = should_start or passive_starter.update(started_ts, location) - - # with 2% left, we killall, otherwise the phone is bricked - should_start = should_start and avail > 0.02 - - # require usb power - should_start = should_start and msg.thermal.usbOnline - - should_start = should_start and accepted_terms and (not do_uninstall) - - # if any CPU gets above 107 or the battery gets above 53, kill all processes - # controls will warn with CPU above 95 or battery above 50 - if max_temp > 107.0 or msg.thermal.bat >= 53000: - should_start = False - - if should_start: - if not started_ts: - params.car_start() - started_ts = sec_since_boot() + if msg.thermal.started: for p in car_started_processes: if p == "loggerd" and logger_dead: kill_managed_process(p) else: start_managed_process(p) else: - started_ts = None logger_dead = False for p in car_started_processes: kill_managed_process(p) - # shutdown if the battery gets lower than 5%, we aren't running, and we are discharging - if msg.thermal.batteryPercent < 5 and msg.thermal.batteryStatus == "Discharging" and battery_was_high: - os.system('LD_LIBRARY_PATH="" svc power shutdown') - if msg.thermal.batteryPercent > 10: - battery_was_high = True - # check the status of all processes, did any of them die? for p in running: cloudlog.debug(" running %s %s" % (p, running[p])) - # report to server once per minute - if (count%60) == 0: - cloudlog.event("STATUS_PACKET", - running=running.keys(), - count=count, - health=(td.to_dict() if td else None), - thermal=msg.to_dict()) - - if do_uninstall: + # is this still needed? + if params.get("DoUninstall") == "1": break - count += 1 - def get_installed_apks(): dat = subprocess.check_output(["pm", "list", "packages", "-f"]).strip().split("\n") ret = {} @@ -532,38 +373,45 @@ def install_apk(path): def update_apks(): # install apks installed = get_installed_apks() - for app in os.listdir(os.path.join(BASEDIR, "apk/")): - if ".apk" in app: - app = app.split(".apk")[0] - if app not in installed: - installed[app] = None + + install_apks = glob.glob(os.path.join(BASEDIR, "apk/*.apk")) + for apk in install_apks: + app = os.path.basename(apk)[:-4] + if app not in installed: + installed[app] = None + cloudlog.info("installed apks %s" % (str(installed), )) for app in installed.iterkeys(): - apk_path = os.path.join(BASEDIR, "apk/"+app+".apk") - if os.path.isfile(apk_path): - h1 = hashlib.sha1(open(apk_path).read()).hexdigest() - h2 = None - if installed[app] is not None: - h2 = hashlib.sha1(open(installed[app]).read()).hexdigest() - cloudlog.info("comparing version of %s %s vs %s" % (app, h1, h2)) - - if h2 is None or h1 != h2: - cloudlog.info("installing %s" % app) + apk_path = os.path.join(BASEDIR, "apk/"+app+".apk") + if not os.path.exists(apk_path): + continue + + h1 = hashlib.sha1(open(apk_path).read()).hexdigest() + h2 = None + if installed[app] is not None: + h2 = hashlib.sha1(open(installed[app]).read()).hexdigest() + cloudlog.info("comparing version of %s %s vs %s" % (app, h1, h2)) + + if h2 is None or h1 != h2: + cloudlog.info("installing %s" % app) + + success = install_apk(apk_path) + if not success: + cloudlog.info("needing to uninstall %s" % app) + system("pm uninstall %s" % app) success = install_apk(apk_path) - if not success: - cloudlog.info("needing to uninstall %s" % app) - system("pm uninstall %s" % app) - success = install_apk(apk_path) - assert success + assert success def manager_update(): + if os.path.exists(os.path.join(BASEDIR, "vpn")): + cloudlog.info("installing vpn") + os.system(os.path.join(BASEDIR, "vpn", "install.sh")) update_apks() def manager_prepare(): - # build cereal first subprocess.check_call(["make", "-j4"], cwd=os.path.join(BASEDIR, "cereal")) @@ -577,9 +425,12 @@ def uninstall(): with open('/cache/recovery/command', 'w') as f: f.write('--wipe_data\n') # IPowerManager.reboot(confirm=false, reason="recovery", wait=true) - os.system("service call power 16 i32 0 s16 recovery i32 1") + os.system("service call power 16 i32 0 s16 recovery i32 1") def main(): + # the flippening! + os.system('LD_LIBRARY_PATH="" content insert --uri content://settings/system --bind name:s:user_rotation --bind value:i:1') + if os.getenv("NOLOG") is not None: del managed_processes['loggerd'] del managed_processes['tombstoned'] @@ -611,22 +462,32 @@ def main(): # set unset params if params.get("IsMetric") is None: params.put("IsMetric", "0") - if params.get("IsRearViewMirror") is None: - params.put("IsRearViewMirror", "0") + if params.get("RecordFront") is None: + params.put("RecordFront", "0") if params.get("IsFcwEnabled") is None: params.put("IsFcwEnabled", "1") if params.get("HasAcceptedTerms") is None: params.put("HasAcceptedTerms", "0") if params.get("IsUploadVideoOverCellularEnabled") is None: params.put("IsUploadVideoOverCellularEnabled", "1") + if params.get("IsDriverMonitoringEnabled") is None: + params.put("IsDriverMonitoringEnabled", "1") + if params.get("IsGeofenceEnabled") is None: + params.put("IsGeofenceEnabled", "-1") + + # is this chffrplus? + if os.getenv("PASSIVE") is not None: + params.put("Passive", str(int(os.getenv("PASSIVE")))) - params.put("Passive", "1" if os.getenv("PASSIVE") else "0") + if params.get("Passive") is None: + raise Exception("Passive must be set to continue") # put something on screen while we set things up if os.getenv("PREPAREONLY") is not None: spinner_proc = None else: - spinner_proc = subprocess.Popen(["./spinner", "loading..."], + spinner_text = "chffrplus" if params.get("Passive")=="1" else "openpilot" + spinner_proc = subprocess.Popen(["./spinner", "loading %s"%spinner_text], cwd=os.path.join(BASEDIR, "selfdrive", "ui", "spinner"), close_fds=True) try: diff --git a/selfdrive/messaging.py b/selfdrive/messaging.py index 119e0d68a4302b..4811f934548f19 100644 --- a/selfdrive/messaging.py +++ b/selfdrive/messaging.py @@ -18,7 +18,7 @@ def sub_sock(context, port, poller=None, addr="127.0.0.1", conflate=False): if conflate: sock.setsockopt(zmq.CONFLATE, 1) sock.connect("tcp://%s:%d" % (addr, port)) - sock.setsockopt(zmq.SUBSCRIBE, "") + sock.setsockopt(zmq.SUBSCRIBE, b"") if poller is not None: poller.register(sock, zmq.POLLIN) return sock diff --git a/selfdrive/orbd/.gitignore b/selfdrive/orbd/.gitignore new file mode 100644 index 00000000000000..829780eb506383 --- /dev/null +++ b/selfdrive/orbd/.gitignore @@ -0,0 +1,8 @@ +orbd +orbd_cpu +test/turbocv_profile +test/turbocv_test +dspout/* +dumb_test +bilinear_lut.h +orb_lut.h diff --git a/selfdrive/orbd/Makefile b/selfdrive/orbd/Makefile new file mode 100644 index 00000000000000..32e9c6dfa549da --- /dev/null +++ b/selfdrive/orbd/Makefile @@ -0,0 +1,105 @@ +# CPU + +CC = clang +CXX = clang++ + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +JSON_FLAGS = -I$(PHONELIBS)/json/src + +CFLAGS = -std=gnu11 -g -O2 -fPIC $(WARN_FLAGS) -Iinclude $(JSON_FLAGS) -I. +CXXFLAGS = -std=c++11 -g -O2 -fPIC $(WARN_FLAGS) -Iinclude $(JSON_FLAGS) -I. +LDFLAGS = + +# profile +# CXXFLAGS += -DTURBOCV_PROFILE=1 + +PHONELIBS = ../../phonelibs +BASEDIR = ../.. +EXTERNAL = ../../external +PYTHONLIBS = + +UNAME_M := $(shell uname -m) + +ifeq ($(UNAME_M),x86_64) +# computer + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(BASEDIR)/external/zmq/lib/ \ + -l:libczmq.a -l:libzmq.a -lpthread + +OPENCV_LIBS = -lopencv_core -lopencv_highgui -lopencv_features2d -lopencv_imgproc + +CXXFLAGS += -fopenmp +LDFLAGS += -lomp + +else +# phone +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +OPENCV_FLAGS = -I$(PHONELIBS)/opencv/include +OPENCV_LIBS = -Wl,--enable-new-dtags -Wl,-rpath,/usr/local/lib/python2.7/site-packages -L/usr/local/lib/python2.7/site-packages -l:cv2.so + +endif + +.PHONY: all +all: orbd + +include ../common/cereal.mk + +DEP_OBJS = ../common/visionipc.o ../common/ipc.o ../common/swaglog.o $(PHONELIBS)/json/src/json.o + +orbd: orbd_dsp.o $(DEP_OBJS) calculator_stub.o freethedsp.o + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(LDFLAGS) \ + $(ZMQ_LIBS) \ + $(CEREAL_LIBS) \ + -L/usr/lib \ + -L/system/vendor/lib64 \ + -ladsprpc \ + -lm -lz -llog + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +orbd_dsp.o: orbd.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + $(CEREAL_CXXFLAGS) \ + $(ZMQ_FLAGS) \ + $(OPENCV_FLAGS) \ + -DDSP \ + -I../ \ + -I../../ \ + -I../../../ \ + -I./include \ + -c -o '$@' '$<' + +freethedsp.o: dsp/freethedsp.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) \ + -c -o '$@' '$<' + +calculator_stub.o: dsp/gen/calculator_stub.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -I./include -c -o '$@' '$<' + +-include internal.mk + +.PHONY: clean +clean: + rm -f *.o turbocv.so orbd test/turbocv_profile test/turbocv_test test/*.o *_lut.h + diff --git a/selfdrive/orbd/dsp/freethedsp.c b/selfdrive/orbd/dsp/freethedsp.c new file mode 100644 index 00000000000000..298f4fd83143b0 --- /dev/null +++ b/selfdrive/orbd/dsp/freethedsp.c @@ -0,0 +1,119 @@ +// freethedsp by geohot +// (because the DSP should be free) +// released under MIT License + +// usage instructions: +// 1. Compile an example from the Qualcomm Hexagon SDK +// 2. Try to run it on your phone +// 3. Be very sad when "adsprpc ... dlopen error: ... signature verify start failed for ..." appears in logcat +// ...here is where people would give up before freethedsp +// 4. Compile freethedsp with 'clang -shared freethedsp.c -o freethedsp.so' (or statically link it to your program) +// 5. Run your program with 'LD_PRELOAD=./freethedsp.so ./' +// 6. OMG THE DSP WORKS +// 7. Be happy. + +// *** patch may have to change for your phone *** + +// this is patching /dsp/fastrpc_shell_0 +// correct if sha hash of fastrpc_shell_0 is "fbadc96848aefad99a95aa4edb560929dcdf78f8" +// patch to return 0xFFFFFFFF from is_test_enabled instead of 0 +// your fastrpc_shell_0 may vary +#define PATCH_ADDR 0x5200c +#define PATCH_OLD "\x40\x3f\x20\x50" +#define PATCH_NEW "\x40\x3f\x00\x5a" +#define PATCH_LEN (sizeof(PATCH_OLD)-1) +#define _BITS_IOCTL_H_ + +// under 100 lines of code begins now +#include +#include +#include +#include +#include + +// ioctl stuff +#define IOC_OUT 0x40000000 /* copy out parameters */ +#define IOC_IN 0x80000000 /* copy in parameters */ +#define IOC_INOUT (IOC_IN|IOC_OUT) +#define IOCPARM_MASK 0x1fff /* parameter length, at most 13 bits */ + +#define _IOC(inout,group,num,len) \ + (inout | ((len & IOCPARM_MASK) << 16) | ((group) << 8) | (num)) +#define _IOWR(g,n,t) _IOC(IOC_INOUT, (g), (n), sizeof(t)) + +// ion ioctls +#include +#define ION_IOC_MSM_MAGIC 'M' +#define ION_IOC_CLEAN_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 2, \ + struct ion_flush_data) + +struct ion_flush_data { + ion_user_handle_t handle; + int fd; + void *vaddr; + unsigned int offset; + unsigned int length; +}; + +// fastrpc ioctls +#define FASTRPC_IOCTL_INIT _IOWR('R', 6, struct fastrpc_ioctl_init) + +struct fastrpc_ioctl_init { + uint32_t flags; /* one of FASTRPC_INIT_* macros */ + uintptr_t __user file; /* pointer to elf file */ + int32_t filelen; /* elf file length */ + int32_t filefd; /* ION fd for the file */ + uintptr_t __user mem; /* mem for the PD */ + int32_t memlen; /* mem length */ + int32_t memfd; /* ION fd for the mem */ +}; + +int ioctl(int fd, unsigned long request, void *arg) { + static void *handle = NULL; + static int (*orig_ioctl)(int, int, void*); + + if (handle == NULL) { + handle = dlopen("/system/lib64/libc.so", RTLD_LAZY); + assert(handle != NULL); + orig_ioctl = dlsym(handle, "ioctl"); + } + + int ret = orig_ioctl(fd, request, arg); + + // carefully modify this one + if (request == FASTRPC_IOCTL_INIT) { + struct fastrpc_ioctl_init *init = (struct fastrpc_ioctl_init *)arg; + + // confirm patch is correct and do the patch + assert(memcmp((void*)(init->mem+PATCH_ADDR), PATCH_OLD, PATCH_LEN) == 0); + memcpy((void*)(init->mem+PATCH_ADDR), PATCH_NEW, PATCH_LEN); + + // flush cache + int ionfd = open("/dev/ion", O_RDONLY); + assert(ionfd > 0); + + struct ion_fd_data fd_data; + fd_data.fd = init->memfd; + int ret = ioctl(ionfd, ION_IOC_IMPORT, &fd_data); + assert(ret == 0); + + struct ion_flush_data flush_data; + flush_data.handle = fd_data.handle; + flush_data.vaddr = (void*)init->mem; + flush_data.offset = 0; + flush_data.length = init->memlen; + ret = ioctl(ionfd, ION_IOC_CLEAN_INV_CACHES, &flush_data); + assert(ret == 0); + + struct ion_handle_data handle_data; + handle_data.handle = fd_data.handle; + ret = ioctl(ionfd, ION_IOC_FREE, &handle_data); + assert(ret == 0); + + // cleanup + close(ionfd); + } + + return ret; +} + diff --git a/selfdrive/orbd/dsp/gen/calculator.h b/selfdrive/orbd/dsp/gen/calculator.h new file mode 100644 index 00000000000000..86a3de6717c833 --- /dev/null +++ b/selfdrive/orbd/dsp/gen/calculator.h @@ -0,0 +1,39 @@ +#ifndef _CALCULATOR_H +#define _CALCULATOR_H + +#include +typedef uint8_t uint8; +typedef uint32_t uint32; + +#ifndef __QAIC_HEADER +#define __QAIC_HEADER(ff) ff +#endif //__QAIC_HEADER + +#ifndef __QAIC_HEADER_EXPORT +#define __QAIC_HEADER_EXPORT +#endif // __QAIC_HEADER_EXPORT + +#ifndef __QAIC_HEADER_ATTRIBUTE +#define __QAIC_HEADER_ATTRIBUTE +#endif // __QAIC_HEADER_ATTRIBUTE + +#ifndef __QAIC_IMPL +#define __QAIC_IMPL(ff) ff +#endif //__QAIC_IMPL + +#ifndef __QAIC_IMPL_EXPORT +#define __QAIC_IMPL_EXPORT +#endif // __QAIC_IMPL_EXPORT + +#ifndef __QAIC_IMPL_ATTRIBUTE +#define __QAIC_IMPL_ATTRIBUTE +#endif // __QAIC_IMPL_ATTRIBUTE +#ifdef __cplusplus +extern "C" { +#endif +__QAIC_HEADER_EXPORT int __QAIC_HEADER(calculator_init)(uint32* leet) __QAIC_HEADER_ATTRIBUTE; +__QAIC_HEADER_EXPORT int __QAIC_HEADER(calculator_extract_and_match)(const uint8* img, int imgLen, uint8* features, int featuresLen) __QAIC_HEADER_ATTRIBUTE; +#ifdef __cplusplus +} +#endif +#endif //_CALCULATOR_H diff --git a/selfdrive/orbd/dsp/gen/calculator_stub.c b/selfdrive/orbd/dsp/gen/calculator_stub.c new file mode 100644 index 00000000000000..66e4a0f822158d --- /dev/null +++ b/selfdrive/orbd/dsp/gen/calculator_stub.c @@ -0,0 +1,613 @@ +#ifndef _CALCULATOR_STUB_H +#define _CALCULATOR_STUB_H +#include "calculator.h" + +// remote.h +#include +#include + +typedef uint32_t remote_handle; +typedef uint64_t remote_handle64; + +typedef struct { + void *pv; + size_t nLen; +} remote_buf; + +typedef struct { + int32_t fd; + uint32_t offset; +} remote_dma_handle; + +typedef union { + remote_buf buf; + remote_handle h; + remote_handle64 h64; + remote_dma_handle dma; +} remote_arg; + +int remote_handle_open(const char* name, remote_handle *ph); +int remote_handle_invoke(remote_handle h, uint32_t dwScalars, remote_arg *pra); +int remote_handle_close(remote_handle h); + +#define REMOTE_SCALARS_MAKEX(nAttr,nMethod,nIn,nOut,noIn,noOut) \ + ((((uint32_t) (nAttr) & 0x7) << 29) | \ + (((uint32_t) (nMethod) & 0x1f) << 24) | \ + (((uint32_t) (nIn) & 0xff) << 16) | \ + (((uint32_t) (nOut) & 0xff) << 8) | \ + (((uint32_t) (noIn) & 0x0f) << 4) | \ + ((uint32_t) (noOut) & 0x0f)) + +#ifndef _QAIC_ENV_H +#define _QAIC_ENV_H + +#ifdef __GNUC__ +#ifdef __clang__ +#pragma GCC diagnostic ignored "-Wunknown-pragmas" +#else +#pragma GCC diagnostic ignored "-Wpragmas" +#endif +#pragma GCC diagnostic ignored "-Wuninitialized" +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-function" +#endif + +#ifndef _ATTRIBUTE_UNUSED + +#ifdef _WIN32 +#define _ATTRIBUTE_UNUSED +#else +#define _ATTRIBUTE_UNUSED __attribute__ ((unused)) +#endif + +#endif // _ATTRIBUTE_UNUSED + +#ifndef __QAIC_REMOTE +#define __QAIC_REMOTE(ff) ff +#endif //__QAIC_REMOTE + +#ifndef __QAIC_HEADER +#define __QAIC_HEADER(ff) ff +#endif //__QAIC_HEADER + +#ifndef __QAIC_HEADER_EXPORT +#define __QAIC_HEADER_EXPORT +#endif // __QAIC_HEADER_EXPORT + +#ifndef __QAIC_HEADER_ATTRIBUTE +#define __QAIC_HEADER_ATTRIBUTE +#endif // __QAIC_HEADER_ATTRIBUTE + +#ifndef __QAIC_IMPL +#define __QAIC_IMPL(ff) ff +#endif //__QAIC_IMPL + +#ifndef __QAIC_IMPL_EXPORT +#define __QAIC_IMPL_EXPORT +#endif // __QAIC_IMPL_EXPORT + +#ifndef __QAIC_IMPL_ATTRIBUTE +#define __QAIC_IMPL_ATTRIBUTE +#endif // __QAIC_IMPL_ATTRIBUTE + +#ifndef __QAIC_STUB +#define __QAIC_STUB(ff) ff +#endif //__QAIC_STUB + +#ifndef __QAIC_STUB_EXPORT +#define __QAIC_STUB_EXPORT +#endif // __QAIC_STUB_EXPORT + +#ifndef __QAIC_STUB_ATTRIBUTE +#define __QAIC_STUB_ATTRIBUTE +#endif // __QAIC_STUB_ATTRIBUTE + +#ifndef __QAIC_SKEL +#define __QAIC_SKEL(ff) ff +#endif //__QAIC_SKEL__ + +#ifndef __QAIC_SKEL_EXPORT +#define __QAIC_SKEL_EXPORT +#endif // __QAIC_SKEL_EXPORT + +#ifndef __QAIC_SKEL_ATTRIBUTE +#define __QAIC_SKEL_ATTRIBUTE +#endif // __QAIC_SKEL_ATTRIBUTE + +#ifdef __QAIC_DEBUG__ + #ifndef __QAIC_DBG_PRINTF__ + #include + #define __QAIC_DBG_PRINTF__( ee ) do { printf ee ; } while(0) + #endif +#else + #define __QAIC_DBG_PRINTF__( ee ) (void)0 +#endif + + +#define _OFFSET(src, sof) ((void*)(((char*)(src)) + (sof))) + +#define _COPY(dst, dof, src, sof, sz) \ + do {\ + struct __copy { \ + char ar[sz]; \ + };\ + *(struct __copy*)_OFFSET(dst, dof) = *(struct __copy*)_OFFSET(src, sof);\ + } while (0) + +#define _COPYIF(dst, dof, src, sof, sz) \ + do {\ + if(_OFFSET(dst, dof) != _OFFSET(src, sof)) {\ + _COPY(dst, dof, src, sof, sz); \ + } \ + } while (0) + +_ATTRIBUTE_UNUSED +static __inline void _qaic_memmove(void* dst, void* src, int size) { + int i; + for(i = 0; i < size; ++i) { + ((char*)dst)[i] = ((char*)src)[i]; + } +} + +#define _MEMMOVEIF(dst, src, sz) \ + do {\ + if(dst != src) {\ + _qaic_memmove(dst, src, sz);\ + } \ + } while (0) + + +#define _ASSIGN(dst, src, sof) \ + do {\ + dst = OFFSET(src, sof); \ + } while (0) + +#define _STD_STRLEN_IF(str) (str == 0 ? 0 : strlen(str)) + +#define AEE_SUCCESS 0 +#define AEE_EOFFSET 0x80000400 +#define AEE_EBADPARM (AEE_EOFFSET + 0x00E) + +#define _TRY(ee, func) \ + do { \ + if (AEE_SUCCESS != ((ee) = func)) {\ + __QAIC_DBG_PRINTF__((__FILE__ ":%d:error:%d:%s\n", __LINE__, (int)(ee),#func));\ + goto ee##bail;\ + } \ + } while (0) + +#define _CATCH(exception) exception##bail: if (exception != AEE_SUCCESS) + +#define _ASSERT(nErr, ff) _TRY(nErr, 0 == (ff) ? AEE_EBADPARM : AEE_SUCCESS) + +#ifdef __QAIC_DEBUG__ +#define _ALLOCATE(nErr, pal, size, alignment, pv) _TRY(nErr, _allocator_alloc(pal, __FILE_LINE__, size, alignment, (void**)&pv)) +#else +#define _ALLOCATE(nErr, pal, size, alignment, pv) _TRY(nErr, _allocator_alloc(pal, 0, size, alignment, (void**)&pv)) +#endif + + +#endif // _QAIC_ENV_H + +#ifndef _ALLOCATOR_H +#define _ALLOCATOR_H + +#include +#include + +typedef struct _heap _heap; +struct _heap { + _heap* pPrev; + const char* loc; + uint64_t buf; +}; + +typedef struct _allocator { + _heap* pheap; + uint8_t* stack; + uint8_t* stackEnd; + int nSize; +} _allocator; + +_ATTRIBUTE_UNUSED +static __inline int _heap_alloc(_heap** ppa, const char* loc, int size, void** ppbuf) { + _heap* pn = 0; + pn = malloc(size + sizeof(_heap) - sizeof(uint64_t)); + if(pn != 0) { + pn->pPrev = *ppa; + pn->loc = loc; + *ppa = pn; + *ppbuf = (void*)&(pn->buf); + return 0; + } else { + return -1; + } +} +#define _ALIGN_SIZE(x, y) (((x) + (y-1)) & ~(y-1)) + +_ATTRIBUTE_UNUSED +static __inline int _allocator_alloc(_allocator* me, + const char* loc, + int size, + unsigned int al, + void** ppbuf) { + if(size < 0) { + return -1; + } else if (size == 0) { + *ppbuf = 0; + return 0; + } + if((_ALIGN_SIZE((uintptr_t)me->stackEnd, al) + size) < (uintptr_t)me->stack + me->nSize) { + *ppbuf = (uint8_t*)_ALIGN_SIZE((uintptr_t)me->stackEnd, al); + me->stackEnd = (uint8_t*)_ALIGN_SIZE((uintptr_t)me->stackEnd, al) + size; + return 0; + } else { + return _heap_alloc(&me->pheap, loc, size, ppbuf); + } +} + +_ATTRIBUTE_UNUSED +static __inline void _allocator_deinit(_allocator* me) { + _heap* pa = me->pheap; + while(pa != 0) { + _heap* pn = pa; + const char* loc = pn->loc; + (void)loc; + pa = pn->pPrev; + free(pn); + } +} + +_ATTRIBUTE_UNUSED +static __inline void _allocator_init(_allocator* me, uint8_t* stack, int stackSize) { + me->stack = stack; + me->stackEnd = stack + stackSize; + me->nSize = stackSize; + me->pheap = 0; +} + + +#endif // _ALLOCATOR_H + +#ifndef SLIM_H +#define SLIM_H + +#include + +//a C data structure for the idl types that can be used to implement +//static and dynamic language bindings fairly efficiently. +// +//the goal is to have a minimal ROM and RAM footprint and without +//doing too many allocations. A good way to package these things seemed +//like the module boundary, so all the idls within one module can share +//all the type references. + + +#define PARAMETER_IN 0x0 +#define PARAMETER_OUT 0x1 +#define PARAMETER_INOUT 0x2 +#define PARAMETER_ROUT 0x3 +#define PARAMETER_INROUT 0x4 + +//the types that we get from idl +#define TYPE_OBJECT 0x0 +#define TYPE_INTERFACE 0x1 +#define TYPE_PRIMITIVE 0x2 +#define TYPE_ENUM 0x3 +#define TYPE_STRING 0x4 +#define TYPE_WSTRING 0x5 +#define TYPE_STRUCTURE 0x6 +#define TYPE_UNION 0x7 +#define TYPE_ARRAY 0x8 +#define TYPE_SEQUENCE 0x9 + +//these require the pack/unpack to recurse +//so it's a hint to those languages that can optimize in cases where +//recursion isn't necessary. +#define TYPE_COMPLEX_STRUCTURE (0x10 | TYPE_STRUCTURE) +#define TYPE_COMPLEX_UNION (0x10 | TYPE_UNION) +#define TYPE_COMPLEX_ARRAY (0x10 | TYPE_ARRAY) +#define TYPE_COMPLEX_SEQUENCE (0x10 | TYPE_SEQUENCE) + + +typedef struct Type Type; + +#define INHERIT_TYPE\ + int32_t nativeSize; /*in the simple case its the same as wire size and alignment*/\ + union {\ + struct {\ + const uintptr_t p1;\ + const uintptr_t p2;\ + } _cast;\ + struct {\ + uint32_t iid;\ + uint32_t bNotNil;\ + } object;\ + struct {\ + const Type *arrayType;\ + int32_t nItems;\ + } array;\ + struct {\ + const Type *seqType;\ + int32_t nMaxLen;\ + } seqSimple; \ + struct {\ + uint32_t bFloating;\ + uint32_t bSigned;\ + } prim; \ + const SequenceType* seqComplex;\ + const UnionType *unionType;\ + const StructType *structType;\ + int32_t stringMaxLen;\ + uint8_t bInterfaceNotNil;\ + } param;\ + uint8_t type;\ + uint8_t nativeAlignment\ + +typedef struct UnionType UnionType; +typedef struct StructType StructType; +typedef struct SequenceType SequenceType; +struct Type { + INHERIT_TYPE; +}; + +struct SequenceType { + const Type * seqType; + uint32_t nMaxLen; + uint32_t inSize; + uint32_t routSizePrimIn; + uint32_t routSizePrimROut; +}; + +//byte offset from the start of the case values for +//this unions case value array. it MUST be aligned +//at the alignment requrements for the descriptor +// +//if negative it means that the unions cases are +//simple enumerators, so the value read from the descriptor +//can be used directly to find the correct case +typedef union CaseValuePtr CaseValuePtr; +union CaseValuePtr { + const uint8_t* value8s; + const uint16_t* value16s; + const uint32_t* value32s; + const uint64_t* value64s; +}; + +//these are only used in complex cases +//so I pulled them out of the type definition as references to make +//the type smaller +struct UnionType { + const Type *descriptor; + uint32_t nCases; + const CaseValuePtr caseValues; + const Type * const *cases; + int32_t inSize; + int32_t routSizePrimIn; + int32_t routSizePrimROut; + uint8_t inAlignment; + uint8_t routAlignmentPrimIn; + uint8_t routAlignmentPrimROut; + uint8_t inCaseAlignment; + uint8_t routCaseAlignmentPrimIn; + uint8_t routCaseAlignmentPrimROut; + uint8_t nativeCaseAlignment; + uint8_t bDefaultCase; +}; + +struct StructType { + uint32_t nMembers; + const Type * const *members; + int32_t inSize; + int32_t routSizePrimIn; + int32_t routSizePrimROut; + uint8_t inAlignment; + uint8_t routAlignmentPrimIn; + uint8_t routAlignmentPrimROut; +}; + +typedef struct Parameter Parameter; +struct Parameter { + INHERIT_TYPE; + uint8_t mode; + uint8_t bNotNil; +}; + +#define SLIM_IFPTR32(is32,is64) (sizeof(uintptr_t) == 4 ? (is32) : (is64)) +#define SLIM_SCALARS_IS_DYNAMIC(u) (((u) & 0x00ffffff) == 0x00ffffff) + +typedef struct Method Method; +struct Method { + uint32_t uScalars; //no method index + int32_t primInSize; + int32_t primROutSize; + int maxArgs; + int numParams; + const Parameter * const *params; + uint8_t primInAlignment; + uint8_t primROutAlignment; +}; + +typedef struct Interface Interface; + +struct Interface { + int nMethods; + const Method * const *methodArray; + int nIIds; + const uint32_t *iids; + const uint16_t* methodStringArray; + const uint16_t* methodStrings; + const char* strings; +}; + + +#endif //SLIM_H + + +#ifndef _CALCULATOR_SLIM_H +#define _CALCULATOR_SLIM_H + +// remote.h + +#include + +#ifndef __QAIC_SLIM +#define __QAIC_SLIM(ff) ff +#endif +#ifndef __QAIC_SLIM_EXPORT +#define __QAIC_SLIM_EXPORT +#endif + +static const Type types[1]; +static const Type types[1] = {{0x1,{{(const uintptr_t)0,(const uintptr_t)0}}, 2,0x1}}; +static const Parameter parameters[3] = {{0x4,{{(const uintptr_t)0,(const uintptr_t)0}}, 2,0x4,3,0},{SLIM_IFPTR32(0x8,0x10),{{(const uintptr_t)&(types[0]),(const uintptr_t)0x0}}, 9,SLIM_IFPTR32(0x4,0x8),0,0},{SLIM_IFPTR32(0x8,0x10),{{(const uintptr_t)&(types[0]),(const uintptr_t)0x0}}, 9,SLIM_IFPTR32(0x4,0x8),3,0}}; +static const Parameter* const parameterArrays[3] = {(&(parameters[1])),(&(parameters[2])),(&(parameters[0]))}; +static const Method methods[2] = {{REMOTE_SCALARS_MAKEX(0,0,0x0,0x1,0x0,0x0),0x0,0x4,1,1,(&(parameterArrays[2])),0x1,0x4},{REMOTE_SCALARS_MAKEX(0,0,0x2,0x1,0x0,0x0),0x8,0x0,5,2,(&(parameterArrays[0])),0x4,0x1}}; +static const Method* const methodArrays[2] = {&(methods[0]),&(methods[1])}; +static const char strings[41] = "extract_and_match\0features\0leet\0init\0img\0"; +static const uint16_t methodStrings[5] = {0,37,18,32,27}; +static const uint16_t methodStringsArrays[2] = {3,0}; +__QAIC_SLIM_EXPORT const Interface __QAIC_SLIM(calculator_slim) = {2,&(methodArrays[0]),0,0,&(methodStringsArrays [0]),methodStrings,strings}; +#endif //_CALCULATOR_SLIM_H +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef _const_calculator_handle +#define _const_calculator_handle ((remote_handle)-1) +#endif //_const_calculator_handle + +static void _calculator_pls_dtor(void* data) { + remote_handle* ph = (remote_handle*)data; + if(_const_calculator_handle != *ph) { + (void)__QAIC_REMOTE(remote_handle_close)(*ph); + *ph = _const_calculator_handle; + } +} + +static int _calculator_pls_ctor(void* ctx, void* data) { + remote_handle* ph = (remote_handle*)data; + *ph = _const_calculator_handle; + if(*ph == (remote_handle)-1) { + return __QAIC_REMOTE(remote_handle_open)((const char*)ctx, ph); + } + return 0; +} + +#if (defined __qdsp6__) || (defined __hexagon__) +#pragma weak adsp_pls_add_lookup +extern int adsp_pls_add_lookup(uint32_t type, uint32_t key, int size, int (*ctor)(void* ctx, void* data), void* ctx, void (*dtor)(void* ctx), void** ppo); +#pragma weak HAP_pls_add_lookup +extern int HAP_pls_add_lookup(uint32_t type, uint32_t key, int size, int (*ctor)(void* ctx, void* data), void* ctx, void (*dtor)(void* ctx), void** ppo); + +__QAIC_STUB_EXPORT remote_handle _calculator_handle(void) { + remote_handle* ph; + if(adsp_pls_add_lookup) { + if(0 == adsp_pls_add_lookup((uint32_t)_calculator_handle, 0, sizeof(*ph), _calculator_pls_ctor, "calculator", _calculator_pls_dtor, (void**)&ph)) { + return *ph; + } + return (remote_handle)-1; + } else if(HAP_pls_add_lookup) { + if(0 == HAP_pls_add_lookup((uint32_t)_calculator_handle, 0, sizeof(*ph), _calculator_pls_ctor, "calculator", _calculator_pls_dtor, (void**)&ph)) { + return *ph; + } + return (remote_handle)-1; + } + return(remote_handle)-1; +} + +#else //__qdsp6__ || __hexagon__ + +uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare); + +#ifdef _WIN32 +#include "Windows.h" +uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare) { + return (uint32_t)InterlockedCompareExchange((volatile LONG*)puDest, (LONG)uExchange, (LONG)uCompare); +} +#elif __GNUC__ +uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare) { + return __sync_val_compare_and_swap(puDest, uCompare, uExchange); +} +#endif //_WIN32 + + +__QAIC_STUB_EXPORT remote_handle _calculator_handle(void) { + static remote_handle handle = _const_calculator_handle; + if((remote_handle)-1 != handle) { + return handle; + } else { + remote_handle tmp; + int nErr = _calculator_pls_ctor("calculator", (void*)&tmp); + if(nErr) { + return (remote_handle)-1; + } + if(((remote_handle)-1 != handle) || ((remote_handle)-1 != (remote_handle)_calculator_atomic_CompareAndExchange((uint32_t*)&handle, (uint32_t)tmp, (uint32_t)-1))) { + _calculator_pls_dtor(&tmp); + } + return handle; + } +} + +#endif //__qdsp6__ + +__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_skel_invoke)(uint32_t _sc, remote_arg* _pra) __QAIC_STUB_ATTRIBUTE { + return __QAIC_REMOTE(remote_handle_invoke)(_calculator_handle(), _sc, _pra); +} + +#ifdef __cplusplus +} +#endif + + +#ifdef __cplusplus +extern "C" { +#endif +extern int remote_register_dma_handle(int, uint32_t); +static __inline int _stub_method(remote_handle _handle, uint32_t _mid, uint32_t _rout0[1]) { + int _numIn[1]; + remote_arg _pra[1]; + uint32_t _primROut[1]; + int _nErr = 0; + _numIn[0] = 0; + _pra[(_numIn[0] + 0)].buf.pv = (void*)_primROut; + _pra[(_numIn[0] + 0)].buf.nLen = sizeof(_primROut); + _TRY(_nErr, __QAIC_REMOTE(remote_handle_invoke)(_handle, REMOTE_SCALARS_MAKEX(0, _mid, 0, 1, 0, 0), _pra)); + _COPY(_rout0, 0, _primROut, 0, 4); + _CATCH(_nErr) {} + return _nErr; +} +__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_init)(uint32* leet) __QAIC_STUB_ATTRIBUTE { + uint32_t _mid = 0; + return _stub_method(_calculator_handle(), _mid, (uint32_t*)leet); +} +static __inline int _stub_method_1(remote_handle _handle, uint32_t _mid, char* _in0[1], uint32_t _in0Len[1], char* _rout1[1], uint32_t _rout1Len[1]) { + int _numIn[1]; + remote_arg _pra[3]; + uint32_t _primIn[2]; + remote_arg* _praIn; + remote_arg* _praROut; + int _nErr = 0; + _numIn[0] = 1; + _pra[0].buf.pv = (void*)_primIn; + _pra[0].buf.nLen = sizeof(_primIn); + _COPY(_primIn, 0, _in0Len, 0, 4); + _praIn = (_pra + 1); + _praIn[0].buf.pv = _in0[0]; + _praIn[0].buf.nLen = (1 * _in0Len[0]); + _COPY(_primIn, 4, _rout1Len, 0, 4); + _praROut = (_praIn + _numIn[0] + 0); + _praROut[0].buf.pv = _rout1[0]; + _praROut[0].buf.nLen = (1 * _rout1Len[0]); + _TRY(_nErr, __QAIC_REMOTE(remote_handle_invoke)(_handle, REMOTE_SCALARS_MAKEX(0, _mid, 2, 1, 0, 0), _pra)); + _CATCH(_nErr) {} + return _nErr; +} +__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_extract_and_match)(const uint8* img, int imgLen, uint8* features, int featuresLen) __QAIC_STUB_ATTRIBUTE { + uint32_t _mid = 1; + return _stub_method_1(_calculator_handle(), _mid, (char**)&img, (uint32_t*)&imgLen, (char**)&features, (uint32_t*)&featuresLen); +} +#ifdef __cplusplus +} +#endif +#endif //_CALCULATOR_STUB_H diff --git a/selfdrive/orbd/dsp/gen/libcalculator_skel.so b/selfdrive/orbd/dsp/gen/libcalculator_skel.so new file mode 100755 index 00000000000000..e48cab48208b0f Binary files /dev/null and b/selfdrive/orbd/dsp/gen/libcalculator_skel.so differ diff --git a/selfdrive/orbd/extractor.h b/selfdrive/orbd/extractor.h new file mode 100644 index 00000000000000..f506cd3868a05d --- /dev/null +++ b/selfdrive/orbd/extractor.h @@ -0,0 +1,38 @@ +#ifndef EXTRACTOR_H +#define EXTRACTOR_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#define ORBD_KEYPOINTS 3000 +#define ORBD_DESCRIPTOR_LENGTH 32 +#define ORBD_HEIGHT 874 +#define ORBD_WIDTH 1164 +#define ORBD_FOCAL 910 + +// matches OrbFeatures from log.capnp +struct orb_features { + // align this + uint16_t n_corners; + uint16_t xy[ORBD_KEYPOINTS][2]; + uint8_t octave[ORBD_KEYPOINTS]; + uint8_t des[ORBD_KEYPOINTS][ORBD_DESCRIPTOR_LENGTH]; + int16_t matches[ORBD_KEYPOINTS]; +}; + +// forward declare this +struct pyramid; + +// manage the pyramids in extractor.c +void init_gpyrs(); +int extract_and_match_gpyrs(const uint8_t *img, struct orb_features *); +int extract_and_match(const uint8_t *img, struct pyramid *pyrs, struct pyramid *prev_pyrs, struct orb_features *); + +#ifdef __cplusplus +} +#endif + +#endif // EXTRACTOR_H diff --git a/selfdrive/orbd/orbd.cc b/selfdrive/orbd/orbd.cc new file mode 100644 index 00000000000000..ce0d47aec6efbd --- /dev/null +++ b/selfdrive/orbd/orbd.cc @@ -0,0 +1,191 @@ +#include +#include +#include +#include +#include +#include +#include + +#include "common/visionipc.h" +#include "common/swaglog.h" + +#include "extractor.h" + +#ifdef DSP +#include "dsp/gen/calculator.h" +#else +#include "turbocv.h" +#endif + +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#ifndef PATH_MAX +#include +#endif + +volatile int do_exit = 0; + +static void set_do_exit(int sig) { + do_exit = 1; +} + +int main(int argc, char *argv[]) { + int err; + setpriority(PRIO_PROCESS, 0, -13); + printf("starting orbd\n"); + +#ifdef DSP + uint32_t test_leet = 0; + char my_path[PATH_MAX+1]; + memset(my_path, 0, sizeof(my_path)); + + ssize_t len = readlink("/proc/self/exe", my_path, sizeof(my_path)); + assert(len > 5); + my_path[len-5] = '\0'; + LOGW("running from %s with PATH_MAX %d", my_path, PATH_MAX); + + char adsp_path[PATH_MAX+1]; + snprintf(adsp_path, PATH_MAX, "ADSP_LIBRARY_PATH=%s/dsp/gen", my_path); + assert(putenv(adsp_path) == 0); + + assert(calculator_init(&test_leet) == 0); + assert(test_leet == 0x1337); + LOGW("orbd init complete"); +#else + init_gpyrs(); +#endif + + signal(SIGINT, (sighandler_t) set_do_exit); + signal(SIGTERM, (sighandler_t) set_do_exit); + + void *ctx = zmq_ctx_new(); + + void *orb_features_sock = zmq_socket(ctx, ZMQ_PUB); + assert(orb_features_sock); + zmq_bind(orb_features_sock, "tcp://*:8058"); + + void *orb_features_summary_sock = zmq_socket(ctx, ZMQ_PUB); + assert(orb_features_summary_sock); + zmq_bind(orb_features_summary_sock, "tcp://*:8062"); + + struct orb_features *features = (struct orb_features *)malloc(sizeof(struct orb_features)); + int last_frame_id = 0; + uint64_t frame_count = 0; + + // every other frame + const int RATE = 2; + + VisionStream stream; + while (!do_exit) { + VisionStreamBufs buf_info; + err = visionstream_init(&stream, VISION_STREAM_YUV, true, &buf_info); + if (err) { + printf("visionstream connect fail\n"); + usleep(100000); + continue; + } + uint64_t timestamp_last_eof = 0; + while (!do_exit) { + VIPCBuf *buf; + VIPCBufExtra extra; + buf = visionstream_get(&stream, &extra); + if (buf == NULL) { + printf("visionstream get failed\n"); + break; + } + + // every other frame + frame_count++; + if ((frame_count%RATE) != 0) { + continue; + } + + uint64_t start = nanos_since_boot(); +#ifdef DSP + int ret = calculator_extract_and_match((uint8_t *)buf->addr, ORBD_HEIGHT*ORBD_WIDTH, (uint8_t *)features, sizeof(struct orb_features)); +#else + int ret = extract_and_match_gpyrs((uint8_t *) buf->addr, features); +#endif + uint64_t end = nanos_since_boot(); + LOGD("total(%d): %6.2f ms to get %4d features on %d", ret, (end-start)/1000000.0, features->n_corners, extra.frame_id); + assert(ret == 0); + + if (last_frame_id+RATE != extra.frame_id) { + LOGW("dropped frame!"); + } + + last_frame_id = extra.frame_id; + + if (timestamp_last_eof == 0) { + timestamp_last_eof = extra.timestamp_eof; + continue; + } + + int match_count = 0; + + // *** send OrbFeatures *** + { + // create capnp message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto orb_features = event.initOrbFeatures(); + + // set timestamps + orb_features.setTimestampEof(extra.timestamp_eof); + orb_features.setTimestampLastEof(timestamp_last_eof); + + // init descriptors for send + kj::ArrayPtr descriptorsPtr = kj::arrayPtr((uint8_t *)features->des, ORBD_DESCRIPTOR_LENGTH * features->n_corners); + orb_features.setDescriptors(descriptorsPtr); + + auto xs = orb_features.initXs(features->n_corners); + auto ys = orb_features.initYs(features->n_corners); + auto octaves = orb_features.initOctaves(features->n_corners); + auto matches = orb_features.initMatches(features->n_corners); + + // copy out normalized keypoints + for (int i = 0; i < features->n_corners; i++) { + xs.set(i, (features->xy[i][0] * 1.0f - ORBD_WIDTH / 2) / ORBD_FOCAL); + ys.set(i, (features->xy[i][1] * 1.0f - ORBD_HEIGHT / 2) / ORBD_FOCAL); + octaves.set(i, features->octave[i]); + matches.set(i, features->matches[i]); + match_count += features->matches[i] != -1; + } + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(orb_features_sock, bytes.begin(), bytes.size(), 0); + } + + // *** send OrbFeaturesSummary *** + + { + // create capnp message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto orb_features_summary = event.initOrbFeaturesSummary(); + + orb_features_summary.setTimestampEof(extra.timestamp_eof); + orb_features_summary.setTimestampLastEof(timestamp_last_eof); + orb_features_summary.setFeatureCount(features->n_corners); + orb_features_summary.setMatchCount(match_count); + orb_features_summary.setComputeNs(end-start); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(orb_features_summary_sock, bytes.begin(), bytes.size(), 0); + } + + timestamp_last_eof = extra.timestamp_eof; + } + } + visionstream_destroy(&stream); + return 0; +} + diff --git a/selfdrive/orbd/orbd_wrapper.sh b/selfdrive/orbd/orbd_wrapper.sh new file mode 100755 index 00000000000000..8ec7443a30d4f7 --- /dev/null +++ b/selfdrive/orbd/orbd_wrapper.sh @@ -0,0 +1,13 @@ +#!/bin/sh +finish() { + echo "exiting orbd" + pkill -SIGINT -P $$ +} + +trap finish EXIT + +while true; do + ./orbd & + wait $! +done + diff --git a/selfdrive/pandad.py b/selfdrive/pandad.py index 7f05a078c94bd7..981546ccf95411 100644 --- a/selfdrive/pandad.py +++ b/selfdrive/pandad.py @@ -10,4 +10,5 @@ def main(gctx=None): os.execvp("./boardd", ["./boardd"]) if __name__ == "__main__": - main() + main() + diff --git a/selfdrive/registration.py b/selfdrive/registration.py index ff522a12e379ee..9b7e6964ef92b5 100644 --- a/selfdrive/registration.py +++ b/selfdrive/registration.py @@ -1,14 +1,16 @@ -import os import json import subprocess from selfdrive.swaglog import cloudlog -from selfdrive.version import version +from selfdrive.version import version, training_version from common.api import api_get from common.params import Params def get_imei(): - return subprocess.check_output(["getprop", "oem.device.imeicache"]).strip() + ret = subprocess.check_output(["getprop", "oem.device.imeicache"]).strip() + if ret == "": + ret = "000000000000000" + return ret def get_serial(): return subprocess.check_output(["getprop", "ro.serialno"]).strip() @@ -25,6 +27,7 @@ def get_git_remote(): def register(): params = Params() params.put("Version", version) + params.put("TrainingVersion", training_version) params.put("GitCommit", get_git_commit()) params.put("GitBranch", get_git_branch()) params.put("GitRemote", get_git_remote()) @@ -47,5 +50,5 @@ def register(): return None if __name__ == "__main__": - print api_get("").text - print register() + print(api_get("").text) + print(register()) diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd index dfeab52461361c..9c48a5f6ac02f3 100755 Binary files a/selfdrive/sensord/gpsd and b/selfdrive/sensord/gpsd differ diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord index 4ad04c9f17d8d7..84137a9b8c2af2 100755 Binary files a/selfdrive/sensord/sensord and b/selfdrive/sensord/sensord differ diff --git a/selfdrive/service_list.yaml b/selfdrive/service_list.yaml index 16dff8002c3eb6..7a875d219b638a 100644 --- a/selfdrive/service_list.yaml +++ b/selfdrive/service_list.yaml @@ -48,8 +48,37 @@ liveMpc: [8035, true] liveLongitudinalMpc: [8036, true] plusFrame: [8037, false] navStatus: [8038, true] +gpsLocationTrimble: [8039, true] +trimbleGnss: [8041, true] +ubloxRaw: [8042, true] +gpsPlannerPoints: [8043, true] +gpsPlannerPlan: [8044, true] +applanixRaw: [8046, true] +orbLocation: [8047, true] +trafficEvents: [8048, true] +liveLocationTiming: [8049, true] +orbslamCorrection: [8050, true] +liveLocationCorrected: [8051, true] +orbObservation: [8052, true] +applanixLocation: [8053, true] +liveLocationKalman: [8054, true] +uiNavigationEvent: [8055, true] +orbOdometry: [8057, true] +orbFeatures: [8058, false] +orbKeyFrame: [8059, true] +uiLayoutState: [8060, true] +frontEncodeIdx: [8061, true] +orbFeaturesSummary: [8062, true] +driverMonitoring: [8063, true] +liveParameters: [8064, true] +liveMapData: [8065, true] testModel: [8040, false] +testLiveLocation: [8045, false] +testJoystick: [8056, false] + +# 8080 is reserved for slave testing daemon +# 8762 is reserved for logserver # manager -- base process to manage starting and stopping of all others # subscribes: health @@ -59,7 +88,7 @@ testModel: [8040, false] # boardd -- communicates with the car # subscribes: sendcan -# publishes: can, health +# publishes: can, health, ubloxRaw # sensord -- publishes the IMU and GPS # publishes: sensorEvents, gpsNMEA diff --git a/selfdrive/services.py b/selfdrive/services.py index d705cd808ae702..bd804afe7926bb 100644 --- a/selfdrive/services.py +++ b/selfdrive/services.py @@ -10,5 +10,5 @@ def __init__(self, port, should_log): service_list = {} with open(service_list_path, "r") as f: - for k, v in yaml.load(f).iteritems(): + for k, v in yaml.load(f).items(): service_list[k] = Service(v[0], v[1]) diff --git a/selfdrive/test/plant/maneuver.py b/selfdrive/test/plant/maneuver.py index af370ea7b6c370..1564aac51deca6 100644 --- a/selfdrive/test/plant/maneuver.py +++ b/selfdrive/test/plant/maneuver.py @@ -1,5 +1,3 @@ -import os -from enum import Enum from maneuverplots import ManeuverPlot from plant import Plant import numpy as np @@ -31,7 +29,6 @@ def evaluate(self): ) last_live100 = None - event_queue = sorted(self.cruise_button_presses, key=lambda a: a[1])[::-1] plot = ManeuverPlot(self.title) buttons_sorted = sorted(self.cruise_button_presses, key=lambda a: a[1]) diff --git a/selfdrive/test/plant/maneuverplots.py b/selfdrive/test/plant/maneuverplots.py index c0bbf6ef94f8f0..36b3e5bf8372e0 100644 --- a/selfdrive/test/plant/maneuverplots.py +++ b/selfdrive/test/plant/maneuverplots.py @@ -63,7 +63,7 @@ def add_data(self, time, gas, brake, steer_torque, distance, speed, def write_plot(self, path, maneuver_name): - title = self.title or maneuver_name + # title = self.title or maneuver_name # TODO: Missing plots from the old one: # long_control_state # proportional_gb, intergral_gb diff --git a/selfdrive/test/plant/plant.py b/selfdrive/test/plant/plant.py index 43b0667726a2e8..29c9e0c330a195 100755 --- a/selfdrive/test/plant/plant.py +++ b/selfdrive/test/plant/plant.py @@ -1,30 +1,29 @@ #!/usr/bin/env python import os import struct - +from collections import namedtuple import zmq import numpy as np from opendbc import DBC_PATH from common.realtime import Ratekeeper - +from selfdrive.config import Conversions as CV import selfdrive.messaging as messaging from selfdrive.services import service_list -from selfdrive.config import CruiseButtons from selfdrive.car.honda.hondacan import fix +from selfdrive.car.honda.values import CAR from selfdrive.car.honda.carstate import get_can_signals from selfdrive.boardd.boardd import can_capnp_to_can_list, can_list_to_can_capnp -from selfdrive.car.honda.old_can_parser import CANParser +from selfdrive.can.plant_can_parser import CANParser from selfdrive.car.honda.interface import CarInterface -from cereal import car from common.dbc import dbc -honda = dbc(os.path.join(DBC_PATH, "honda_civic_touring_2016_can.dbc")) +honda = dbc(os.path.join(DBC_PATH, "honda_civic_touring_2016_can_generated.dbc")) # Trick: set 0x201 (interceptor) in fingerprints for gas is controlled like if there was an interceptor -CP = CarInterface.get_params("HONDA CIVIC 2016 TOURING", {0x201}) +CP = CarInterface.get_params(CAR.CIVIC, {0x201}) def car_plant(pos, speed, grade, gas, brake): @@ -37,7 +36,6 @@ def car_plant(pos, speed, grade, gas, brake): speed_base = power_peak/force_peak rolling_res = 0.01 g = 9.81 - wheel_r = 0.31 frontal_area = 2.2 air_density = 1.225 gas_to_peak_linear_slope = 3.33 @@ -58,7 +56,7 @@ def car_plant(pos, speed, grade, gas, brake): creep_accel = np.interp(speed, creep_accel_bp, creep_accel_v) force_creep = creep_accel * mass - force_resistance = -(rolling_res * mass * g + 0.5 * speed**2 * aero_cd * air_density) + force_resistance = -(rolling_res * mass * g + 0.5 * speed**2 * aero_cd * air_density * frontal_area) force = force_gas + force_brake + force_resistance + force_grade + force_creep acceleration = force / mass @@ -66,7 +64,7 @@ def car_plant(pos, speed, grade, gas, brake): return speed, acceleration def get_car_can_parser(): - dbc_f = 'honda_civic_touring_2016_can.dbc' + dbc_f = 'honda_civic_touring_2016_can_generated.dbc' signals = [ ("STEER_TORQUE", 0xe4, 0), ("STEER_TORQUE_REQUEST", 0xe4, 0), @@ -92,8 +90,6 @@ class Plant(object): def __init__(self, lead_relevancy=False, rate=100, speed=0.0, distance_lead=2.0): self.rate = rate - self.civic = True - self.brake_only = False if not Plant.messaging_initialized: context = zmq.Context() @@ -143,13 +139,13 @@ def speed_sensor(self, speed): if speed<0.3: return 0 else: - return speed + return speed * CV.MS_TO_KPH def current_time(self): return float(self.rk.frame) / self.rate def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True): - gen_dbc, gen_signals, gen_checks = get_can_signals(CP) + gen_signals, gen_checks = get_can_signals(CP) sgs = [s[0] for s in gen_signals] msgs = [s[1] for s in gen_signals] cks_msgs = set(check[0] for check in gen_checks) @@ -173,7 +169,7 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) fcw = True if self.cp.vl[0x1fa]['COMPUTER_BRAKE_REQUEST']: - brake = self.cp.vl[0x1fa]['COMPUTER_BRAKE'] + brake = self.cp.vl[0x1fa]['COMPUTER_BRAKE'] * 0.003906248 else: brake = 0.0 @@ -191,7 +187,6 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) # ******** run the car ******** speed, acceleration = car_plant(self.distance_prev, self.speed_prev, grade, gas, brake) - standstill = (speed == 0) distance = self.distance_prev + speed * self.ts speed = self.speed_prev + self.ts * acceleration if speed <= 0: @@ -208,7 +203,6 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) else: d_rel = 200. v_rel = 0. - a_rel = 0 lateral_pos_rel = 0. # print at 5hz @@ -216,16 +210,68 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) print "%6.2f m %6.2f m/s %6.2f m/s2 %.2f ang gas: %.2f brake: %.2f steer: %5.2f lead_rel: %6.2f m %6.2f m/s" % (distance, speed, acceleration, self.angle_steer, gas, brake, steer_torque, d_rel, v_rel) # ******** publish the car ******** - vls = [self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), - self.angle_steer, self.angle_steer_rate, 0, self.gear_choice, speed!=0, - 0, 0, 0, 0, - self.v_cruise, not self.seatbelt, self.seatbelt, self.brake_pressed, 0., - self.user_gas, cruise_buttons, self.esp_disabled, 0, - self.user_brake, self.steer_error, self.brake_error, - self.brake_error, self.gear_shifter, self.main_on, self.acc_status, - self.pedal_gas, self.cruise_setting, - # append one more zero for gas interceptor - 0,0,0,0,0,0] + vls_tuple = namedtuple('vls', [ + 'XMISSION_SPEED', + 'WHEEL_SPEED_FL', 'WHEEL_SPEED_FR', 'WHEEL_SPEED_RL', 'WHEEL_SPEED_RR', + 'STEER_ANGLE', 'STEER_ANGLE_RATE', 'STEER_TORQUE_SENSOR', + 'LEFT_BLINKER', 'RIGHT_BLINKER', + 'GEAR', + 'WHEELS_MOVING', + 'BRAKE_ERROR_1', 'BRAKE_ERROR_2', + 'SEATBELT_DRIVER_LAMP', 'SEATBELT_DRIVER_LATCHED', + 'BRAKE_PRESSED', 'BRAKE_SWITCH', + 'CRUISE_BUTTONS', + 'ESP_DISABLED', + 'HUD_LEAD', + 'USER_BRAKE', + 'STEER_STATUS', + 'GEAR_SHIFTER', + 'PEDAL_GAS', + 'CRUISE_SETTING', + 'ACC_STATUS', + + 'CRUISE_SPEED_PCM', + 'CRUISE_SPEED_OFFSET', + + 'DOOR_OPEN_FL', 'DOOR_OPEN_FR', 'DOOR_OPEN_RL', 'DOOR_OPEN_RR', + + 'CAR_GAS', + 'MAIN_ON', + 'EPB_STATE', + 'BRAKE_HOLD_ACTIVE', + 'INTERCEPTOR_GAS', + ]) + vls = vls_tuple( + self.speed_sensor(speed), + self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), + self.angle_steer, self.angle_steer_rate, 0, #Steer torque sensor + 0, 0, # Blinkers + self.gear_choice, + speed != 0, + self.brake_error, self.brake_error, + not self.seatbelt, self.seatbelt, # Seatbelt + self.brake_pressed, 0., #Brake pressed, Brake switch + cruise_buttons, + self.esp_disabled, + 0, # HUD lead + self.user_brake, + self.steer_error, + self.gear_shifter, + self.pedal_gas, + self.cruise_setting, + self.acc_status, + + self.v_cruise, + 0, # Cruise speed offset + + 0, 0, 0, 0, # Doors + + self.user_gas, + self.main_on, + 0, # EPB State + 0, # Brake hold + 0 # Interceptor feedback + ) # TODO: publish each message at proper frequency can_msgs = [] @@ -233,11 +279,12 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) msg_struct = {} indxs = [i for i, x in enumerate(msgs) if msg == msgs[i]] for i in indxs: - msg_struct[sgs[i]] = vls[i] + msg_struct[sgs[i]] = getattr(vls, sgs[i]) if "COUNTER" in honda.get_signals(msg): msg_struct["COUNTER"] = self.rk.frame % 4 + msg = honda.lookup_msg_id(msg) msg_data = honda.encode(msg, msg_struct) if "CHECKSUM" in honda.get_signals(msg): @@ -255,6 +302,14 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) "0f00000" can_msgs.append([0x400, 0, radar_state_msg, 1]) can_msgs.append([0x445, 0, radar_msg.decode("hex"), 1]) + + # add camera msg so controlsd thinks it's alive + msg_struct["COUNTER"] = self.rk.frame % 4 + msg = honda.lookup_msg_id(0xe4) + msg_data = honda.encode(msg, msg_struct) + msg_data = fix(msg_data, 0xe4) + can_msgs.append([0xe4, 0, msg_data, 2]) + Plant.logcan.send(can_list_to_can_capnp(can_msgs).to_bytes()) # ******** publish a fake model going straight and fake calibration ******** @@ -294,12 +349,7 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) def plant_thread(rate=100): plant = Plant(rate) while 1: - if plant.rk.frame%100 >= 20 and plant.rk.frame%100 <= 25: - cruise_buttons = CruiseButtons.RES_ACCEL - else: - cruise_buttons = 0 plant.step() if __name__ == "__main__": plant_thread() - diff --git a/selfdrive/test/plant/plant_ui.py b/selfdrive/test/plant/plant_ui.py index fed1234ca70ae6..d7b4bf1856fdc9 100755 --- a/selfdrive/test/plant/plant_ui.py +++ b/selfdrive/test/plant/plant_ui.py @@ -1,7 +1,7 @@ #!/usr/bin/env python import pygame from plant import Plant -from selfdrive.config import CruiseButtons +from selfdrive.car.honda.values import CruiseButtons import numpy as np import selfdrive.messaging as messaging import math @@ -21,7 +21,7 @@ def rot_center(image, angle): return rot_image def car_w_color(c): - car = pygame.Surface((METER*CAR_LENGTH, METER*CAR_LENGTH)) + car = pygame.Surface((METER*CAR_LENGTH, METER*CAR_LENGTH)) # pylint: disable=too-many-function-args car.set_alpha(0) car.fill((10,10,10)) car.set_alpha(128) @@ -101,9 +101,9 @@ def pt_from_car(pt): for x,y in control_pts: pygame.draw.circle(display, (255,255,0), (int(x * METER),int(y * METER)), 2) - # draw path + # draw path path_pts = zip(np.arange(0, 50), md.model.path.points) - + for x,y in path_pts: x,y = pt_from_car((x,y)) pygame.draw.circle(display, (0,255,0), (int(x * METER),int(y * METER)), 1) @@ -118,5 +118,3 @@ def pt_from_car(pt): """ pygame.display.flip() - - diff --git a/selfdrive/test/test_openpilot.py b/selfdrive/test/test_openpilot.py index 81fd2042a9435f..0a825e3a34cb1b 100644 --- a/selfdrive/test/test_openpilot.py +++ b/selfdrive/test/test_openpilot.py @@ -4,7 +4,6 @@ from common.testing import phone_only from selfdrive.manager import manager_init, manager_prepare from selfdrive.manager import start_managed_process, kill_managed_process, get_running -from selfdrive.config import CruiseButtons from functools import wraps import time diff --git a/selfdrive/test/tests/plant/test_longitudinal.py b/selfdrive/test/tests/plant/test_longitudinal.py index 73380022b8a513..e5affb62765d45 100755 --- a/selfdrive/test/tests/plant/test_longitudinal.py +++ b/selfdrive/test/tests/plant/test_longitudinal.py @@ -9,7 +9,8 @@ import matplotlib matplotlib.use('svg') -from selfdrive.config import Conversions as CV, CruiseButtons as CB +from selfdrive.config import Conversions as CV +from selfdrive.car.honda.values import CruiseButtons as CB from selfdrive.test.plant.maneuver import Maneuver import selfdrive.manager as manager from common.params import Params @@ -94,6 +95,16 @@ def create_dir(path): speed_lead_breakpoints = [0., 15., 25.0], cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] ), + Maneuver( + 'steady state following a car at 20m/s, then lead decel to 0mph at 3m/s^2', + duration=50., + initial_speed = 20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values = [20., 20., 0.], + speed_lead_breakpoints = [0., 15., 21.66], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), Maneuver( 'starting at 0mph, approaching a stopped car 100m away', duration=30., diff --git a/selfdrive/thermal.py b/selfdrive/thermal.py deleted file mode 100644 index 24e4d6c52f0283..00000000000000 --- a/selfdrive/thermal.py +++ /dev/null @@ -1,19 +0,0 @@ -"""Methods for reading system thermal information.""" -import selfdrive.messaging as messaging - -def read_tz(x): - with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: - ret = max(0, int(f.read())) - return ret - -def read_thermal(): - dat = messaging.new_message() - dat.init('thermal') - dat.thermal.cpu0 = read_tz(5) - dat.thermal.cpu1 = read_tz(7) - dat.thermal.cpu2 = read_tz(10) - dat.thermal.cpu3 = read_tz(12) - dat.thermal.mem = read_tz(2) - dat.thermal.gpu = read_tz(16) - dat.thermal.bat = read_tz(29) - return dat diff --git a/selfdrive/thermald.py b/selfdrive/thermald.py new file mode 100755 index 00000000000000..4238273d97ec7d --- /dev/null +++ b/selfdrive/thermald.py @@ -0,0 +1,294 @@ +#!/usr/bin/env python2.7 +import os +import zmq +from smbus2 import SMBus +from cereal import log +from selfdrive.version import training_version +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging +from selfdrive.services import service_list +from selfdrive.loggerd.config import ROOT +from common.params import Params +from common.realtime import sec_since_boot +from common.numpy_fast import clip +from common.filter_simple import FirstOrderFilter + +ThermalStatus = log.ThermalData.ThermalStatus +CURRENT_TAU = 2. # 2s time constant + +def read_tz(x): + with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: + ret = max(0, int(f.read())) + return ret + +def read_thermal(): + dat = messaging.new_message() + dat.init('thermal') + dat.thermal.cpu0 = read_tz(5) + dat.thermal.cpu1 = read_tz(7) + dat.thermal.cpu2 = read_tz(10) + dat.thermal.cpu3 = read_tz(12) + dat.thermal.mem = read_tz(2) + dat.thermal.gpu = read_tz(16) + dat.thermal.bat = read_tz(29) + return dat + +LEON = False +def setup_eon_fan(): + global LEON + + os.system("echo 2 > /sys/module/dwc3_msm/parameters/otg_switch") + + bus = SMBus(7, force=True) + try: + bus.write_byte_data(0x21, 0x10, 0xf) # mask all interrupts + bus.write_byte_data(0x21, 0x03, 0x1) # set drive current and global interrupt disable + bus.write_byte_data(0x21, 0x02, 0x2) # needed? + bus.write_byte_data(0x21, 0x04, 0x4) # manual override source + except IOError: + print "LEON detected" + #os.system("echo 1 > /sys/devices/soc/6a00000.ssusb/power_supply/usb/usb_otg") + LEON = True + bus.close() + +last_eon_fan_val = None +def set_eon_fan(val): + global LEON, last_eon_fan_val + + if last_eon_fan_val is None or last_eon_fan_val != val: + bus = SMBus(7, force=True) + if LEON: + try: + i = [0x1, 0x3 | 0, 0x3 | 0x08, 0x3 | 0x10][val] + bus.write_i2c_block_data(0x3d, 0, [i]) + except IOError: + # tusb320 + if val == 0: + bus.write_i2c_block_data(0x67, 0xa, [0]) + else: + bus.write_i2c_block_data(0x67, 0xa, [0x20]) + bus.write_i2c_block_data(0x67, 0x8, [(val-1)<<6]) + else: + bus.write_byte_data(0x21, 0x04, 0x2) + bus.write_byte_data(0x21, 0x03, (val*2)+1) + bus.write_byte_data(0x21, 0x04, 0x4) + bus.close() + last_eon_fan_val = val + +# temp thresholds to control fan speed - high hysteresis +_TEMP_THRS_H = [50., 65., 80., 10000] +# temp thresholds to control fan speed - low hysteresis +_TEMP_THRS_L = [42.5, 57.5, 72.5, 10000] +# fan speed options +_FAN_SPEEDS = [0, 16384, 32768, 65535] +# max fan speed only allowed if battery is hot +_BAT_TEMP_THERSHOLD = 45. + +def handle_fan(max_cpu_temp, bat_temp, fan_speed): + new_speed_h = next(speed for speed, temp_h in zip(_FAN_SPEEDS, _TEMP_THRS_H) if temp_h > max_cpu_temp) + new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_cpu_temp) + + if new_speed_h > fan_speed: + # update speed if using the high thresholds results in fan speed increment + fan_speed = new_speed_h + elif new_speed_l < fan_speed: + # update speed if using the low thresholds results in fan speed decrement + fan_speed = new_speed_l + + if bat_temp < _BAT_TEMP_THERSHOLD: + # no max fan speed unless battery is hot + fan_speed = min(fan_speed, _FAN_SPEEDS[-2]) + + set_eon_fan(fan_speed/16384) + + return fan_speed + +class LocationStarter(object): + def __init__(self): + self.last_good_loc = 0 + def update(self, started_ts, location): + rt = sec_since_boot() + + if location is None or location.accuracy > 50 or location.speed < 2: + # bad location, stop if we havent gotten a location in a while + # dont stop if we're been going for less than a minute + if started_ts: + if rt-self.last_good_loc > 60. and rt-started_ts > 60: + cloudlog.event("location_stop", + ts=rt, + started_ts=started_ts, + last_good_loc=self.last_good_loc, + location=location.to_dict() if location else None) + return False + else: + return True + else: + return False + + self.last_good_loc = rt + + if started_ts: + return True + else: + cloudlog.event("location_start", location=location.to_dict() if location else None) + return location.speed*3.6 > 10 + +def thermald_thread(): + setup_eon_fan() + + # prevent LEECO from undervoltage + BATT_PERC_OFF = 10 if LEON else 3 + + # now loop + context = zmq.Context() + thermal_sock = messaging.pub_sock(context, service_list['thermal'].port) + health_sock = messaging.sub_sock(context, service_list['health'].port) + location_sock = messaging.sub_sock(context, service_list['gpsLocation'].port) + fan_speed = 0 + count = 0 + + off_ts = None + started_ts = None + ignition_seen = False + started_seen = False + passive_starter = LocationStarter() + thermal_status = ThermalStatus.green + health_sock.RCVTIMEO = 1500 + current_filter = FirstOrderFilter(0., CURRENT_TAU, 1.) + + params = Params() + + while 1: + health = messaging.recv_sock(health_sock, wait=True) + location = messaging.recv_sock(location_sock) + location = location.gpsLocation if location else None + msg = read_thermal() + + # loggerd is gated based on free space + statvfs = os.statvfs(ROOT) + avail = (statvfs.f_bavail * 1.0)/statvfs.f_blocks + + # thermal message now also includes free space + msg.thermal.freeSpace = avail + with open("/sys/class/power_supply/battery/capacity") as f: + msg.thermal.batteryPercent = int(f.read()) + with open("/sys/class/power_supply/battery/status") as f: + msg.thermal.batteryStatus = f.read().strip() + with open("/sys/class/power_supply/battery/current_now") as f: + msg.thermal.batteryCurrent = int(f.read()) + with open("/sys/class/power_supply/battery/voltage_now") as f: + msg.thermal.batteryVoltage = int(f.read()) + with open("/sys/class/power_supply/usb/online") as f: + msg.thermal.usbOnline = bool(int(f.read())) + + current_filter.update(msg.thermal.batteryCurrent / 1e6) + msg.thermal.chargerDisabled = current_filter.x > 1.0 # if current is ? 1A out, then charger might be off + + # TODO: add car battery voltage check + max_cpu_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, + msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 + max_comp_temp = max(max_cpu_temp, msg.thermal.mem / 10., msg.thermal.gpu / 10.) + bat_temp = msg.thermal.bat/1000. + fan_speed = handle_fan(max_cpu_temp, bat_temp, fan_speed) + msg.thermal.fanSpeed = fan_speed + + # thermal logic with hysterisis + if max_cpu_temp > 107. or bat_temp >= 63.: + # onroad not allowed + thermal_status = ThermalStatus.danger + elif max_comp_temp > 95. or bat_temp > 60.: + # hysteresis between onroad not allowed and engage not allowed + thermal_status = clip(thermal_status, ThermalStatus.red, ThermalStatus.danger) + elif max_cpu_temp > 90.0: + # hysteresis between engage not allowed and uploader not allowed + thermal_status = clip(thermal_status, ThermalStatus.yellow, ThermalStatus.red) + elif max_cpu_temp > 85.0: + # uploader not allowed + thermal_status = ThermalStatus.yellow + elif max_cpu_temp > 75.0: + # hysteresis between uploader not allowed and all good + thermal_status = clip(thermal_status, ThermalStatus.green, ThermalStatus.yellow) + else: + # all good + thermal_status = ThermalStatus.green + + # **** starting logic **** + + # start constellation of processes when the car starts + ignition = health is not None and health.health.started + ignition_seen = ignition_seen or ignition + + # add voltage check for ignition + if not ignition_seen and health is not None and health.health.voltage > 13500: + ignition = True + + do_uninstall = params.get("DoUninstall") == "1" + accepted_terms = params.get("HasAcceptedTerms") == "1" + completed_training = params.get("CompletedTrainingVersion") == training_version + + should_start = ignition + + # have we seen a panda? + passive = (params.get("Passive") == "1") + + # start on gps movement if we haven't seen ignition and are in passive mode + should_start = should_start or (not (ignition_seen and health) # seen ignition and panda is connected + and passive + and passive_starter.update(started_ts, location)) + + # with 2% left, we killall, otherwise the phone will take a long time to boot + should_start = should_start and msg.thermal.freeSpace > 0.02 + + # require usb power in passive mode + should_start = should_start and (not passive or msg.thermal.usbOnline) + + # confirm we have completed training and aren't uninstalling + should_start = should_start and accepted_terms and (passive or completed_training) and (not do_uninstall) + + # if any CPU gets above 107 or the battery gets above 63, kill all processes + # controls will warn with CPU above 95 or battery above 60 + if thermal_status >= ThermalStatus.danger: + # TODO: Add a better warning when this is happening + should_start = False + + if should_start: + off_ts = None + if started_ts is None: + params.car_start() + started_ts = sec_since_boot() + started_seen = True + else: + started_ts = None + if off_ts is None: + off_ts = sec_since_boot() + + # shutdown if the battery gets lower than 3%, it's discharging, we aren't running for + # more than a minute but we were running + if msg.thermal.batteryPercent < BATT_PERC_OFF and msg.thermal.batteryStatus == "Discharging" and \ + started_seen and (sec_since_boot() - off_ts) > 60: + os.system('LD_LIBRARY_PATH="" svc power shutdown') + + msg.thermal.started = started_ts is not None + msg.thermal.startedTs = int(1e9*(started_ts or 0)) + + msg.thermal.thermalStatus = thermal_status + thermal_sock.send(msg.to_bytes()) + print msg + + # report to server once per minute + if (count%60) == 0: + cloudlog.event("STATUS_PACKET", + count=count, + health=(health.to_dict() if health else None), + location=(location.to_dict() if location else None), + thermal=msg.to_dict()) + + count += 1 + + +def main(gctx=None): + thermald_thread() + +if __name__ == "__main__": + main() + diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index 430b31d8811a15..bac43a0a19772a 100644 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -7,7 +7,7 @@ from raven import Client from raven.transport.http import HTTPTransport -from selfdrive.version import version +from selfdrive.version import version, dirty from selfdrive.swaglog import cloudlog def get_tombstones(): @@ -69,7 +69,7 @@ def main(gctx): initial_tombstones = set(get_tombstones()) client = Client('https://d3b175702f62402c91ade04d1c547e68:b20d68c813c74f63a7cdf9c4039d8f56@sentry.io/157615', - install_sys_hook=False, transport=HTTPTransport) + install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty}) while True: now_tombstones = set(get_tombstones()) diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile index 38b91479353dd9..a78a48cf2a9193 100644 --- a/selfdrive/ui/Makefile +++ b/selfdrive/ui/Makefile @@ -25,13 +25,25 @@ CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o NANOVG_FLAGS = -I$(PHONELIBS)/nanovg JSON_FLAGS = -I$(PHONELIBS)/json/src +OPENCL_FLAGS = -I$(PHONELIBS)/opencl/include +OPENCL_LIBS = -lgsl -lCB -lOpenCL + OPENGL_LIBS = -lGLESv3 +OPENSL_LIBS = -lOpenSLES + FRAMEBUFFER_LIBS = -lutils -lgui -lEGL -OBJS = ui.o \ +CFLAGS += -DQCOM +CXXFLAGS += -DQCOM + +OBJS = slplay.o \ + ui.o \ ../common/glutil.o \ ../common/visionipc.o \ + ../common/ipc.o \ + ../common/visionimg.o \ + ../common/visionbuf_ion.o \ ../common/framebuffer.o \ ../common/params.o \ ../common/util.o \ @@ -52,27 +64,42 @@ ui: $(OBJS) $(CEREAL_LIBS) \ $(ZMQ_LIBS) \ -L/system/vendor/lib64 \ - -lhardware \ + -lhardware -lui \ $(OPENGL_LIBS) \ - -lcutils -lm -llog + $(OPENCL_LIBS) \ + ${OPENSL_LIBS} \ + -Wl,-rpath=/system/lib64,-rpath=/system/comma/usr/lib \ + -lcutils -lm -llog -lui -ladreno_utils + +slplay.o: slplay.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -fPIC \ + -I../ \ + $(OPENSL_LIBS) \ + -c -o '$@' $^ %.o: %.cc @echo "[ CXX ] $@" $(CXX) $(CXXFLAGS) -MMD \ -Iinclude -I.. -I../.. \ + $(OPENCL_FLAGS) \ -I$(PHONELIBS)/android_frameworks_native/include \ -I$(PHONELIBS)/android_system_core/include \ -I$(PHONELIBS)/android_hardware_libhardware/include \ + -I$(PHONELIBS)/libgralloc/include \ + -I$(PHONELIBS)/linux/include \ -c -o '$@' '$<' %.o: %.c @echo "[ CC ] $@" $(CC) $(CFLAGS) -MMD \ - -I.. -I../.. \ + -Iinclude -I.. -I../.. \ $(NANOVG_FLAGS) \ $(ZMQ_FLAGS) \ $(CEREAL_CFLAGS) \ $(JSON_FLAGS) \ + $(OPENCL_FLAGS) \ + -I$(PHONELIBS)/linux/include \ -c -o '$@' '$<' .PHONY: clean diff --git a/selfdrive/ui/slplay.c b/selfdrive/ui/slplay.c new file mode 100644 index 00000000000000..6e5d8b95389140 --- /dev/null +++ b/selfdrive/ui/slplay.c @@ -0,0 +1,184 @@ +#include +#include +#include +#include +#include + +#include "common/timing.h" +#include "slplay.h" + +SLEngineItf engineInterface = NULL; +SLObjectItf outputMix = NULL; +SLObjectItf engine = NULL; +uri_player players[32] = {{NULL, NULL, NULL}}; + +uint64_t loop_start = 0; +uint64_t loop_start_ctx = 0; + +uri_player* get_player_by_uri(const char* uri) { + for (uri_player *s = players; s->uri != NULL; s++) { + if (strcmp(s->uri, uri) == 0) { + return s; + } + } + + return NULL; +} + +uri_player* slplay_create_player_for_uri(const char* uri, char **error) { + uri_player player = { uri, NULL, NULL }; + + SLresult result; + SLDataLocator_URI locUri = {SL_DATALOCATOR_URI, (SLchar *) uri}; + SLDataFormat_MIME formatMime = {SL_DATAFORMAT_MIME, NULL, SL_CONTAINERTYPE_UNSPECIFIED}; + SLDataSource audioSrc = {&locUri, &formatMime}; + + SLDataLocator_OutputMix outMix = {SL_DATALOCATOR_OUTPUTMIX, outputMix}; + SLDataSink audioSnk = {&outMix, NULL}; + + result = (*engineInterface)->CreateAudioPlayer(engineInterface, &player.player, &audioSrc, &audioSnk, 0, NULL, NULL); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to create audio player"); + return NULL; + } + + result = (*(player.player))->Realize(player.player, SL_BOOLEAN_FALSE); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize audio player"); + return NULL; + } + + result = (*(player.player))->GetInterface(player.player, SL_IID_PLAY, &(player.playInterface)); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to get player interface"); + return NULL; + } + + result = (*(player.playInterface))->SetPlayState(player.playInterface, SL_PLAYSTATE_PAUSED); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to initialize playstate to SL_PLAYSTATE_PAUSED"); + return NULL; + } + + uri_player *p = players; + while (p->uri != NULL) { + p++; + } + *p = player; + + return p; +} + +void slplay_setup(char **error) { + SLresult result; + SLEngineOption engineOptions[] = {{SL_ENGINEOPTION_THREADSAFE, SL_BOOLEAN_TRUE}}; + result = slCreateEngine(&engine, 1, engineOptions, 0, NULL, NULL); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to create OpenSL engine"); + } + + result = (*engine)->Realize(engine, SL_BOOLEAN_FALSE); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize OpenSL engine"); + } + + result = (*engine)->GetInterface(engine, SL_IID_ENGINE, &engineInterface); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize OpenSL engine"); + } + + const SLInterfaceID ids[1] = {SL_IID_VOLUME}; + const SLboolean req[1] = {SL_BOOLEAN_FALSE}; + result = (*engineInterface)->CreateOutputMix(engineInterface, &outputMix, 1, ids, req); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to create output mix"); + } + + result = (*outputMix)->Realize(outputMix, SL_BOOLEAN_FALSE); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize output mix"); + } +} + +void slplay_destroy() { + for (uri_player *player = players; player->uri != NULL; player++) { + if (player->player) { + (*(player->player))->Destroy(player->player); + } + } + + (*outputMix)->Destroy(outputMix); + (*engine)->Destroy(engine); +} + +void slplay_stop (uri_player* player, char **error) { + SLPlayItf playInterface = player->playInterface; + SLresult result; + + // stop a loop + loop_start = 0; + + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PAUSED); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to set SL_PLAYSTATE_STOPPED"); + return; + } +} + +void slplay_stop_uri(const char* uri, char **error) { + uri_player* player = get_player_by_uri(uri); + slplay_stop(player, error); +} + +void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event) { + uint64_t cb_loop_start = *((uint64_t*)context); + if (event == SL_PLAYEVENT_HEADATEND && cb_loop_start == loop_start) { + (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_STOPPED); + (*playItf)->SetMarkerPosition(playItf, 0); + (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_PLAYING); + } +} + +void slplay_play (const char *uri, bool loop, char **error) { + SLresult result; + + uri_player* player = get_player_by_uri(uri); + if (player == NULL) { + player = slplay_create_player_for_uri(uri, error); + if (*error) { + return; + } + } + + SLPlayItf playInterface = player->playInterface; + if (loop) { + loop_start = nanos_since_boot(); + loop_start_ctx = loop_start; + result = (*playInterface)->RegisterCallback(playInterface, slplay_callback, &loop_start_ctx); + if (result != SL_RESULT_SUCCESS) { + char error[64]; + snprintf(error, sizeof(error), "Failed to register callback. %d", result); + *error = error[0]; + return; + } + + result = (*playInterface)->SetCallbackEventsMask(playInterface, SL_PLAYEVENT_HEADATEND); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to set callback event mask"); + return; + } + } + + // Reset the audio player + result = (*playInterface)->ClearMarkerPosition(playInterface); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to clear marker position"); + return; + } + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PAUSED); + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_STOPPED); + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PLAYING); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to set SL_PLAYSTATE_PLAYING"); + } +} diff --git a/selfdrive/ui/slplay.h b/selfdrive/ui/slplay.h new file mode 100644 index 00000000000000..f8c39ceeb7cb2c --- /dev/null +++ b/selfdrive/ui/slplay.h @@ -0,0 +1,21 @@ +#ifndef SLPLAY_H +#define SLPLAY_H + +#include +#include +#include + +typedef struct { + const char* uri; + SLObjectItf player; + SLPlayItf playInterface; +} uri_player; + +void slplay_setup(char **error); +uri_player* slplay_create_player_for_uri(const char* uri, char **error); +void slplay_play (const char *uri, bool loop, char **error); +void slplay_stop_uri (const char* uri, char **error); +void slplay_destroy(); + +#endif + diff --git a/selfdrive/ui/spinner/spinner b/selfdrive/ui/spinner/spinner index 5e9a473389c36d..326a377aa3ffde 100755 Binary files a/selfdrive/ui/spinner/spinner and b/selfdrive/ui/spinner/spinner differ diff --git a/selfdrive/ui/spinner/spinner.c b/selfdrive/ui/spinner/spinner.c index f67e310a03b71b..477cfe1cf3abd1 100644 --- a/selfdrive/ui/spinner/spinner.c +++ b/selfdrive/ui/spinner/spinner.c @@ -15,7 +15,6 @@ #include "common/framebuffer.h" - int main(int argc, char** argv) { int err; @@ -35,40 +34,63 @@ int main(int argc, char** argv) { NVGcontext *vg = nvgCreateGLES3(NVG_ANTIALIAS | NVG_STENCIL_STROKES); assert(vg); - int font = nvgCreateFont(vg, "Bold", "../../assets/courbd.ttf"); + int font = nvgCreateFont(vg, "Bold", "../../assets/OpenSans-SemiBold.ttf"); assert(font >= 0); + int spinner_img = nvgCreateImage(vg, "../../assets/img_spinner_track.png", 0); + assert(spinner_img >= 0); + int spinner_img_s = 360; + int spinner_img_x = ((fb_w/2)-(spinner_img_s/2)); + int spinner_img_y = 260; + int spinner_img_xc = (fb_w/2); + int spinner_img_yc = (fb_h/2)-100; + int spinner_comma_img = nvgCreateImage(vg, "../../assets/img_spinner_comma.png", 0); + assert(spinner_comma_img >= 0); + for (int cnt = 0; ; cnt++) { glClearColor(0.1, 0.1, 0.1, 1.0); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); - glEnable(GL_BLEND); glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); nvgBeginFrame(vg, fb_w, fb_h, 1.0f); - - for (int k=0; k<3; k++) { - float ang = (2*M_PI * (float)cnt / 120.0) + (k / 3.0) * 2*M_PI; - - nvgBeginPath(vg); - nvgStrokeColor(vg, nvgRGBA(255, 255, 255, 255)); - nvgStrokeWidth(vg, 5); - - nvgMoveTo(vg, fb_w/2 + 50 * cosf(ang), fb_h/2 + 50 * sinf(ang)); - nvgLineTo(vg, fb_w/2 + 15 * cosf(ang), fb_h/2 + 15 * sinf(ang)); - nvgMoveTo(vg, fb_w/2 - 15 * cosf(ang), fb_h/2 - 15 * sinf(ang)); - nvgLineTo(vg, fb_w/2 - 50 * cosf(ang), fb_h/2 - 50 * sinf(ang)); - nvgStroke(vg); - } - + // background + nvgBeginPath(vg); + NVGpaint bg = nvgLinearGradient(vg, fb_w, 0, fb_w, fb_h, + nvgRGBA(0, 0, 0, 175), nvgRGBA(0, 0, 0, 255)); + nvgFillPaint(vg, bg); + nvgRect(vg, 0, 0, fb_w, fb_h); + nvgFill(vg); + + // spin track + nvgSave(vg); + nvgTranslate(vg, spinner_img_xc, spinner_img_yc); + nvgRotate(vg, (3.75*M_PI * cnt/120.0)); + nvgTranslate(vg, -spinner_img_xc, -spinner_img_yc); + NVGpaint spinner_imgPaint = nvgImagePattern(vg, spinner_img_x, spinner_img_y, + spinner_img_s, spinner_img_s, 0, spinner_img, 0.6f); + nvgBeginPath(vg); + nvgFillPaint(vg, spinner_imgPaint); + nvgRect(vg, spinner_img_x, spinner_img_y, spinner_img_s, spinner_img_s); + nvgFill(vg); + nvgRestore(vg); + + // comma + NVGpaint comma_imgPaint = nvgImagePattern(vg, spinner_img_x, spinner_img_y, + spinner_img_s, spinner_img_s, 0, spinner_comma_img, 1.0f); + nvgBeginPath(vg); + nvgFillPaint(vg, comma_imgPaint); + nvgRect(vg, spinner_img_x, spinner_img_y, spinner_img_s, spinner_img_s); + nvgFill(vg); + + // message if (spintext) { nvgTextAlign(vg, NVG_ALIGN_CENTER | NVG_ALIGN_TOP); nvgFontSize(vg, 96.0f); - nvgText(vg, fb_w / 2, fb_h*2/3, spintext, NULL); + nvgText(vg, fb_w/2, (fb_h*2/3)+24, spintext, NULL); } nvgEndFrame(vg); - eglSwapBuffers(display, surface); assert(glGetError() == GL_NO_ERROR); } diff --git a/selfdrive/ui/start.sh b/selfdrive/ui/start.sh new file mode 100755 index 00000000000000..89704a5b6edf93 --- /dev/null +++ b/selfdrive/ui/start.sh @@ -0,0 +1,6 @@ +#!/bin/sh +set -e + +make +export LD_LIBRARY_PATH=/system/lib64:$LD_LIBRARY_PATH +exec ./ui diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c index 20f23df800cb92..ce57dd46517e75 100644 --- a/selfdrive/ui/ui.c +++ b/selfdrive/ui/ui.c @@ -4,11 +4,12 @@ #include #include #include +#include #include #include -#include +#include #include #include @@ -27,15 +28,12 @@ #include "common/touch.h" #include "common/framebuffer.h" #include "common/visionipc.h" +#include "common/visionimg.h" #include "common/modeldata.h" #include "common/params.h" #include "cereal/gen/c/log.capnp.h" - -// Calibration status values from controlsd.py -#define CALIBRATION_UNCALIBRATED 0 -#define CALIBRATION_CALIBRATED 1 -#define CALIBRATION_INVALID 2 +#include "slplay.h" #define STATUS_STOPPED 0 #define STATUS_DISENGAGED 1 @@ -44,13 +42,27 @@ #define STATUS_ALERT 4 #define STATUS_MAX 5 -#define UI_BUF_COUNT 4 +#define ALERTSIZE_NONE 0 +#define ALERTSIZE_SMALL 1 +#define ALERTSIZE_MID 2 +#define ALERTSIZE_FULL 3 +#define UI_BUF_COUNT 4 -const int box_x = 330; -const int box_y = 30; -const int box_width = 1560; -const int box_height = 1020; +const int vwp_w = 1920; +const int vwp_h = 1080; +const int nav_w = 640; +const int nav_ww= 760; +const int sbr_w = 300; +const int bdr_s = 30; +const int box_x = sbr_w+bdr_s; +const int box_y = bdr_s; +const int box_w = vwp_w-sbr_w-(bdr_s*2); +const int box_h = vwp_h-(bdr_s*2); +const int viz_w = vwp_w-(bdr_s*2); +const int header_h = 420; +const int footer_h = 280; +const int footer_y = vwp_h-bdr_s-footer_h; const uint8_t bg_colors[][4] = { [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xff}, @@ -61,17 +73,30 @@ const uint8_t bg_colors[][4] = { }; const uint8_t alert_colors[][4] = { - [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0x80}, - [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0x80}, - [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0x80}, - [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0x80}, - [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0x80}, + [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xf1}, + [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0xc8}, + [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0xf1}, + [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0xf1}, + [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0xf1}, }; +const int alert_sizes[] = { + [ALERTSIZE_NONE] = 0, + [ALERTSIZE_SMALL] = 241, + [ALERTSIZE_MID] = 390, + [ALERTSIZE_FULL] = vwp_h, +}; + +// TODO: this is also hardcoded in common/transformations/camera.py +const mat3 intrinsic_matrix = (mat3){{ + 910., 0., 582., + 0., 910., 437., + 0., 0., 1. +}}; + typedef struct UIScene { int frontview; - - uint8_t *bgr_ptr; + int fullview; int transformed_width, transformed_height; @@ -88,27 +113,41 @@ typedef struct UIScene { float v_cruise; uint64_t v_cruise_update_ts; float v_ego; + + float speedlimit; + bool speedlimit_valid; + float curvature; int engaged; + bool engageable; + bool monitoring_active; + + bool uilayout_sidebarcollapsed; + bool uilayout_mapenabled; + // responsive layout + int ui_viz_rx; + int ui_viz_rw; + int ui_viz_ro; int lead_status; float lead_d_rel, lead_y_rel, lead_v_rel; - uint8_t *bgr_front_ptr; int front_box_x, front_box_y, front_box_width, front_box_height; uint64_t alert_ts; char alert_text1[1024]; char alert_text2[1024]; uint8_t alert_size; + float alert_blinkingrate; float awareness_status; uint64_t started_ts; - // Used to display calibration progress - int cal_status; - int cal_perc; + // Used to show gps planner status + bool gps_planner_active; + + bool is_playing_alert; } UIScene; typedef struct UIState { @@ -125,6 +164,9 @@ typedef struct UIState { int font_courbd; int font_sans_regular; int font_sans_semibold; + int font_sans_bold; + int img_wheel; + int img_face; zsock_t *thermal_sock; void *thermal_sock_raw; @@ -140,6 +182,11 @@ typedef struct UIState { void *livempc_sock_raw; zsock_t *plus_sock; void *plus_sock_raw; + zsock_t *map_data_sock; + void *map_data_sock_raw; + + zsock_t *uilayout_sock; + void *uilayout_sock_raw; int plus_state; @@ -154,8 +201,9 @@ typedef struct UIState { int cur_vision_front_idx; GLuint frame_program; + GLuint frame_texs[UI_BUF_COUNT]; + GLuint frame_front_texs[UI_BUF_COUNT]; - GLuint frame_tex; GLint frame_pos_loc, frame_texcoord_loc; GLint frame_texture_loc, frame_transform_loc; @@ -163,32 +211,35 @@ typedef struct UIState { GLint line_pos_loc, line_color_loc; GLint line_transform_loc; - unsigned int rgb_width, rgb_height; + unsigned int rgb_width, rgb_height, rgb_stride; + size_t rgb_buf_len; mat4 rgb_transform; - unsigned int rgb_front_width, rgb_front_height; - GLuint frame_front_tex; - - bool intrinsic_matrix_loaded; - mat3 intrinsic_matrix; + unsigned int rgb_front_width, rgb_front_height, rgb_front_stride; + size_t rgb_front_buf_len; UIScene scene; bool awake; int awake_timeout; + int volume_timeout; + int status; bool is_metric; bool passive; + char alert_type[64]; + char alert_sound[64]; + int alert_size; + float alert_blinking_alpha; + bool alert_blinked; float light_sensor; } UIState; static int last_brightness = -1; -static void set_brightness(int brightness) { - if (last_brightness != brightness) { - //printf("setting brightness %d\n", brightness); - // can't hurt +static void set_brightness(UIState *s, int brightness) { + if (last_brightness != brightness && (s->awake || brightness == 0)) { FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); if (f != NULL) { fprintf(f, "%d", brightness); @@ -211,11 +262,21 @@ static void set_awake(UIState *s, bool awake) { framebuffer_set_power(s->fb, HWC_POWER_MODE_NORMAL); } else { LOG("awake off"); + set_brightness(s, 0); framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); } } } +static void set_volume(UIState *s, int volume) { + char volume_change_cmd[64]; + sprintf(volume_change_cmd, "service call audio 3 i32 3 i32 %d i32 1", volume); + + // 5 second timeout at 60fps + s->volume_timeout = 5 * 60; + int volume_changed = system(volume_change_cmd); +} + volatile int do_exit = 0; static void set_do_exit(int sig) { do_exit = 1; @@ -266,14 +327,59 @@ static const mat4 device_transform = {{ 0.0, 0.0, 0.0, 1.0, }}; -// frame from 4/3 to box size with a 2x zoon +// frame from 4/3 to box size with a 2x zoom static const mat4 frame_transform = {{ - 2*(4./3.)/((float)box_width/box_height), 0.0, 0.0, 0.0, + 2*(4./3.)/((float)viz_w/box_h), 0.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, }}; +// frame from 4/3 to 16/9 display +static const mat4 full_to_wide_frame_transform = {{ + .75, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + +typedef struct { + const char* name; + const char* uri; + bool loop; +} sound_file; + +sound_file sound_table[] = { + { "chimeDisengage", "../assets/sounds/disengaged.wav", false }, + { "chimeEngage", "../assets/sounds/engaged.wav", false }, + { "chimeWarning1", "../assets/sounds/warning_1.wav", false }, + { "chimeWarning2", "../assets/sounds/warning_2.wav", false }, + { "chimeWarningRepeat", "../assets/sounds/warning_2.wav", true }, + { "chimeError", "../assets/sounds/error.wav", false }, + { "chimePrompt", "../assets/sounds/error.wav", false }, + { NULL, NULL, false }, +}; + +sound_file* get_sound_file_by_name(const char* name) { + for (sound_file *s = sound_table; s->name != NULL; s++) { + if (strcmp(s->name, name) == 0) { + return s; + } + } + + return NULL; +} + +void ui_sound_init(char **error) { + slplay_setup(error); + if (*error) return; + + for (sound_file *s = sound_table; s->name != NULL; s++) { + slplay_create_player_for_uri(s->uri, error); + if (*error) return; + } +} + static void ui_init(UIState *s) { memset(s, 0, sizeof(UIState)); @@ -294,6 +400,10 @@ static void ui_init(UIState *s) { assert(s->live100_sock); s->live100_sock_raw = zsock_resolve(s->live100_sock); + s->uilayout_sock = zsock_new_sub(">tcp://127.0.0.1:8060", ""); + assert(s->uilayout_sock); + s->uilayout_sock_raw = zsock_resolve(s->uilayout_sock); + s->livecalibration_sock = zsock_new_sub(">tcp://127.0.0.1:8019", ""); assert(s->livecalibration_sock); s->livecalibration_sock_raw = zsock_resolve(s->livecalibration_sock); @@ -310,6 +420,10 @@ static void ui_init(UIState *s) { assert(s->plus_sock); s->plus_sock_raw = zsock_resolve(s->plus_sock); + s->map_data_sock = zsock_new_sub(">tcp://127.0.0.1:8065", ""); + assert(s->map_data_sock); + s->map_data_sock_raw = zsock_resolve(s->map_data_sock); + s->ipc_fd = -1; // init display @@ -329,6 +443,14 @@ static void ui_init(UIState *s) { assert(s->font_sans_regular >= 0); s->font_sans_semibold = nvgCreateFont(s->vg, "sans-semibold", "../assets/OpenSans-SemiBold.ttf"); assert(s->font_sans_semibold >= 0); + s->font_sans_bold = nvgCreateFont(s->vg, "sans-bold", "../assets/OpenSans-Bold.ttf"); + assert(s->font_sans_bold >= 0); + + assert(s->img_wheel >= 0); + s->img_wheel = nvgCreateImage(s->vg, "../assets/img_chffr_wheel.png", 1); + + assert(s->img_face >= 0); + s->img_face = nvgCreateImage(s->vg, "../assets/img_driver_face.png", 1); // init gl s->frame_program = load_program(frame_vertex_shader, frame_fragment_shader); @@ -363,39 +485,6 @@ static void ui_init(UIState *s) { } } - -// If the intrinsics are in the params entry, this copies them to -// intrinsic_matrix and returns true. Otherwise returns false. -static bool try_load_intrinsics(mat3 *intrinsic_matrix) { - char *value; - const int result = read_db_value(NULL, "CloudCalibration", &value, NULL); - - if (result == 0) { - JsonNode* calibration_json = json_decode(value); - free(value); - - JsonNode *intrinsic_json = - json_find_member(calibration_json, "intrinsic_matrix"); - - if (intrinsic_json == NULL || intrinsic_json->tag != JSON_ARRAY) { - json_delete(calibration_json); - return false; - } - - int i = 0; - JsonNode* json_num; - json_foreach(json_num, intrinsic_json) { - intrinsic_matrix->v[i++] = json_num->number_; - } - json_delete(calibration_json); - - return true; - } else { - return false; - } -} - - static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, int num_back_fds, const int *back_fds, const VisionStreamBufs front_bufs, int num_front_fds, @@ -412,8 +501,8 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, s->cur_vision_front_idx = -1; s->scene = (UIScene){ - .frontview = 0, - .cal_status = CALIBRATION_CALIBRATED, + .frontview = getenv("FRONTVIEW") != NULL, + .fullview = getenv("FULLVIEW") != NULL, .transformed_width = ui_info.transformed_width, .transformed_height = ui_info.transformed_height, .front_box_x = ui_info.front_box_x, @@ -421,13 +510,18 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, .front_box_width = ui_info.front_box_width, .front_box_height = ui_info.front_box_height, .world_objects_visible = false, // Invisible until we receive a calibration message. + .gps_planner_active = false, }; s->rgb_width = back_bufs.width; s->rgb_height = back_bufs.height; + s->rgb_stride = back_bufs.stride; + s->rgb_buf_len = back_bufs.buf_len; s->rgb_front_width = front_bufs.width; s->rgb_front_height = front_bufs.height; + s->rgb_front_stride = front_bufs.stride; + s->rgb_front_buf_len = front_bufs.buf_len; s->rgb_transform = (mat4){{ 2.0/s->rgb_width, 0.0, 0.0, -1.0, @@ -444,36 +538,6 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, } } -static bool ui_alert_active(UIState *s) { - return (nanos_since_boot() - s->scene.alert_ts) < 20000000000ULL && - strlen(s->scene.alert_text1) > 0 && - s->scene.alert_size == cereal_Live100Data_AlertSize_full; -} - -static void ui_update_frame(UIState *s) { - assert(glGetError() == GL_NO_ERROR); - - UIScene *scene = &s->scene; - - if (scene->frontview && scene->bgr_front_ptr) { - // load front frame texture - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, - s->rgb_front_width, s->rgb_front_height, - GL_RGB, GL_UNSIGNED_BYTE, scene->bgr_front_ptr); - } else if (!scene->frontview && scene->bgr_ptr) { - // load frame texture - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, s->frame_tex); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, - s->rgb_width, s->rgb_height, - GL_RGB, GL_UNSIGNED_BYTE, scene->bgr_ptr); - } - - assert(glGetError() == GL_NO_ERROR); -} - static void ui_draw_transformed_box(UIState *s, uint32_t color) { const UIScene *scene = &s->scene; @@ -522,39 +586,32 @@ vec3 car_space_to_full_frame(const UIState *s, vec4 car_space_projective) { // The last entry is zero because of how we store E (to use matvecmul). const vec3 Ep = {{Ep4.v[0], Ep4.v[1], Ep4.v[2]}}; - const vec3 KEp = matvecmul3(s->intrinsic_matrix, Ep); + const vec3 KEp = matvecmul3(intrinsic_matrix, Ep); // Project. const vec3 p_image = {{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2], 1.}}; return p_image; } +// Calculate an interpolation between two numbers at a specific increment +static float lerp(float v0, float v1, float t) { + return (1 - t) * v0 + t * v1; +} -// TODO: refactor with draw_path -static void draw_cross(UIState *s, float x_in, float y_in, float sz, NVGcolor color) { +static void draw_chevron(UIState *s, float x_in, float y_in, float sz, + NVGcolor fillColor, NVGcolor glowColor) { const UIScene *scene = &s->scene; nvgSave(s->vg); - // path coords are worked out in rgb-box space nvgTranslate(s->vg, 240.0f, 0.0); - - // zooom in 2x nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); nvgScale(s->vg, 2.0, 2.0); - nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); - nvgBeginPath(s->vg); - nvgStrokeColor(s->vg, color); - nvgStrokeWidth(s->vg, 5); - const vec4 p_car_space = (vec4){{x_in, y_in, 0., 1.}}; const vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - // scale with distance - // x_in = 0 -> sz = 30 (max) - // x_in = 90 -> sz = 15 (min) sz *= 30; sz /= (x_in / 3 + 30); if (sz > 30) sz = 30; @@ -562,51 +619,58 @@ static void draw_cross(UIState *s, float x_in, float y_in, float sz, NVGcolor co float x = p_full_frame.v[0]; float y = p_full_frame.v[1]; - if (x >= 0 && y >= 0.) { - nvgMoveTo(s->vg, x-sz, y); - nvgLineTo(s->vg, x+sz, y); - nvgMoveTo(s->vg, x, y-sz); - nvgLineTo(s->vg, x, y+sz); + // glow + nvgBeginPath(s->vg); + float g_xo = sz/5; + float g_yo = sz/10; + if (x >= 0 && y >= 0.) { + nvgMoveTo(s->vg, x+(sz*1.35)+g_xo, y+sz+g_yo); + nvgLineTo(s->vg, x, y-g_xo); + nvgLineTo(s->vg, x-(sz*1.35)-g_xo, y+sz+g_yo); + nvgLineTo(s->vg, x+(sz*1.35)+g_xo, y+sz+g_yo); + nvgClosePath(s->vg); + } + nvgFillColor(s->vg, glowColor); + nvgFill(s->vg); - nvgStroke(s->vg); + // chevron + nvgBeginPath(s->vg); + if (x >= 0 && y >= 0.) { + nvgMoveTo(s->vg, x+(sz*1.25), y+sz); + nvgLineTo(s->vg, x, y); + nvgLineTo(s->vg, x-(sz*1.25), y+sz); + nvgLineTo(s->vg, x+(sz*1.25), y+sz); + nvgClosePath(s->vg); } + nvgFillColor(s->vg, fillColor); + nvgFill(s->vg); nvgRestore(s->vg); } -static void draw_x_y(UIState *s, const float *x_coords, const float *y_coords, size_t num_points, - NVGcolor color) { +static void ui_draw_lane_line(UIState *s, const float *points, float off, + NVGcolor color, bool is_ghost) { const UIScene *scene = &s->scene; nvgSave(s->vg); - - // path coords are worked out in rgb-box space - nvgTranslate(s->vg, 240.0f, 0.0); - - // zooom in 2x - nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgTranslate(s->vg, 240.0f, 0.0); // rgb-box space + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); // zoom 2x nvgScale(s->vg, 2.0, 2.0); - nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); - nvgBeginPath(s->vg); - nvgStrokeColor(s->vg, color); - nvgStrokeWidth(s->vg, 2); - bool started = false; - for (int i=0; ivg, x, y); started = true; @@ -615,41 +679,69 @@ static void draw_x_y(UIState *s, const float *x_coords, const float *y_coords, s } } - nvgStroke(s->vg); + for (int i=49; i>0; i--) { + float px = (float)i; + float py = is_ghost?(points[i]-off):(points[i]+off); + vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x < 0 || y < 0.) { + continue; + } + nvgLineTo(s->vg, x, y); + } + nvgClosePath(s->vg); + nvgFillColor(s->vg, color); + nvgFill(s->vg); nvgRestore(s->vg); } -static void draw_path(UIState *s, const float *points, float off, - NVGcolor color) { +static void ui_draw_lane(UIState *s, const PathData path, NVGcolor color) { + ui_draw_lane_line(s, path.points, 0.025*path.prob, color, false); + float var = min(path.std, 0.7); + color.a /= 4; + ui_draw_lane_line(s, path.points, -var, color, true); + ui_draw_lane_line(s, path.points, var, color, true); +} + +static void ui_draw_track(UIState *s, bool is_mpc) { const UIScene *scene = &s->scene; + const PathData path = scene->model.path; + const float *mpc_x_coords = &scene->mpc_x[0]; + const float *mpc_y_coords = &scene->mpc_y[0]; nvgSave(s->vg); - - // path coords are worked out in rgb-box space - nvgTranslate(s->vg, 240.0f, 0.0); - - // zooom in 2x - nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgTranslate(s->vg, 240.0f, 0.0); // rgb-box space + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); // zoom 2x nvgScale(s->vg, 2.0, 2.0); - nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); - nvgBeginPath(s->vg); - nvgStrokeColor(s->vg, color); - nvgStrokeWidth(s->vg, 5); - bool started = false; - for (int i=0; i<50; i++) { - float px = (float)i; - float py = points[i] + off; + bool started = false; + float off = is_mpc?0.3:0.5; + float lead_d = scene->lead_d_rel*2.; + float path_height = is_mpc?(lead_d>5.)?min(lead_d, 25.)-min(lead_d*0.35, 10.):20. + :(lead_d>0.)?min(lead_d, 50.)-min(lead_d*0.35, 10.):49.; + + // left side up + for (int i=0; i<=path_height; i++) { + float px, py, mpx; + if (is_mpc) { + mpx = i==0?0.0:mpc_x_coords[i]; + px = lerp(mpx+1.0, mpx, i/100.0); + py = mpc_y_coords[i] - off; + } else { + px = lerp(i+1.0, i, i/100.0); + py = path.points[i] - off; + } vec4 p_car_space = (vec4){{px, py, 0., 1.}}; vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - float x = p_full_frame.v[0]; float y = p_full_frame.v[1]; - if (x < 0 || y < 0.) { + if (x < 0 || y < 0) { continue; } @@ -661,52 +753,80 @@ static void draw_path(UIState *s, const float *points, float off, } } - nvgStroke(s->vg); + // right side down + for (int i=path_height; i>=0; i--) { + float px, py, mpx; + if (is_mpc) { + mpx = i==0?0.0:mpc_x_coords[i]; + px = lerp(mpx+1.0, mpx, i/100.0); + py = mpc_y_coords[i] + off; + } else { + px = lerp(i+1.0, i, i/100.0); + py = path.points[i] + off; + } - nvgRestore(s->vg); -} + vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x < 0 || y < 0.) { + continue; + } -static void draw_model_path(UIState *s, const PathData path, NVGcolor color) { - float var = min(path.std, 0.7); - draw_path(s, path.points, 0.0, color); - color.a /= 4; - draw_path(s, path.points, -var, color); - draw_path(s, path.points, var, color); + nvgLineTo(s->vg, x, y); + } + + nvgClosePath(s->vg); + + NVGpaint track_bg; + if (is_mpc) { + // Draw colored MPC track + const uint8_t *clr = bg_colors[s->status]; + track_bg = nvgLinearGradient(s->vg, vwp_w, vwp_h, vwp_w, vwp_h*.4, + nvgRGBA(clr[0], clr[1], clr[2], 255), nvgRGBA(clr[0], clr[1], clr[2], 255/2)); + } else { + // Draw white vision track + track_bg = nvgLinearGradient(s->vg, vwp_w, vwp_h, vwp_w, vwp_h*.4, + nvgRGBA(255, 255, 255, 255), nvgRGBA(255, 255, 255, 0)); + } + + nvgFillPaint(s->vg, track_bg); + nvgFill(s->vg); + nvgRestore(s->vg); } static void draw_steering(UIState *s, float curvature) { - float points[50]; for (int i = 0; i < 50; i++) { float y_actual = i * tan(asin(clamp(i * curvature, -0.999, 0.999)) / 2.); points[i] = y_actual; } - draw_path(s, points, 0.0, nvgRGBA(0, 0, 255, 128)); + // ui_draw_lane_edge(s, points, 0.0, nvgRGBA(0, 0, 255, 128), 5); } static void draw_frame(UIState *s) { - // draw frame texture const UIScene *scene = &s->scene; - mat4 out_mat; float x1, x2, y1, y2; if (s->scene.frontview) { - out_mat = device_transform; // full 16/9 - // flip horizontally so it looks like a mirror - x2 = (float)scene->front_box_x / s->rgb_front_width; - x1 = (float)(scene->front_box_x + scene->front_box_width) / s->rgb_front_width; + x1 = 0.0; + x2 = 1.0; + y1 = 1.0; + y2 = 0.0; + } else { + x1 = 1.0; + x2 = 0.0; + y1 = 1.0; + y2 = 0.0; + } - y1 = (float)scene->front_box_y / s->rgb_front_height; - y2 = (float)(scene->front_box_y + scene->front_box_height) / s->rgb_front_height; + mat4 out_mat; + if (s->scene.frontview || s->scene.fullview) { + out_mat = matmul(device_transform, full_to_wide_frame_transform); } else { out_mat = matmul(device_transform, frame_transform); - - x1 = 0.0; - x2 = 1.0; - y1 = 0.0; - y2 = 1.0; } const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3}; @@ -718,10 +838,10 @@ static void draw_frame(UIState *s) { }; glActiveTexture(GL_TEXTURE0); - if (s->scene.frontview) { - glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); - } else { - glBindTexture(GL_TEXTURE_2D, s->frame_tex); + if (s->scene.frontview && s->cur_vision_front_idx >= 0) { + glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[s->cur_vision_front_idx]); + } else if (!scene->frontview && s->cur_vision_idx >= 0) { + glBindTexture(GL_TEXTURE_2D, s->frame_texs[s->cur_vision_idx]); } glUseProgram(s->frame_program); @@ -741,36 +861,25 @@ static void draw_frame(UIState *s) { glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, &frame_indicies[0]); } -/* - * Draw a rect at specific position with specific dimensions - */ -static void ui_draw_rounded_rect( - NVGcontext* c, - int x, - int y, - int width, - int height, - int radius, - NVGcolor color -) { - - int bottom_x = x + width; - int bottom_y = y + height; - - nvgBeginPath(c); - - // Position the rect - nvgRoundedRect(c, x, y, bottom_x, bottom_y, radius); - - // Color the rect - nvgFillColor(c, color); - - // Draw the rect - nvgFill(c); - - // Draw white border around rect - nvgStrokeColor(c, nvgRGBA(255,255,255,200)); - nvgStroke(c); +static void ui_draw_vision_lanes(UIState *s) { + const UIScene *scene = &s->scene; + // Draw left lane edge + ui_draw_lane( + s, scene->model.left_lane, + nvgRGBAf(1.0, 1.0, 1.0, scene->model.left_lane.prob)); + + // Draw right lane edge + ui_draw_lane( + s, scene->model.right_lane, + nvgRGBAf(1.0, 1.0, 1.0, scene->model.right_lane.prob)); + + // Draw vision path + ui_draw_track(s, false); + + if (scene->engaged) { + // Draw MPC path when engaged + ui_draw_track(s, true); + } } // Draw all world space objects. @@ -780,327 +889,380 @@ static void ui_draw_world(UIState *s) { return; } - //draw_steering(s, scene->curvature); - if ((nanos_since_boot() - scene->model_ts) < 1000000000ULL) { - int left_lane_color = (int)(255 * scene->model.left_lane.prob); - int right_lane_color = (int)(255 * scene->model.right_lane.prob); - draw_model_path( - s, scene->model.left_lane, - nvgRGBA(left_lane_color, left_lane_color, left_lane_color, 128)); - draw_model_path( - s, scene->model.right_lane, - nvgRGBA(right_lane_color, right_lane_color, right_lane_color, 128)); - - // draw paths - draw_path(s, scene->model.path.points, 0.0f, nvgRGBA(0xc0, 0xc0, 0xc0, 255)); - - // draw MPC only if engaged - if (scene->engaged) { - draw_x_y(s, &scene->mpc_x[1], &scene->mpc_y[1], 19, nvgRGBA(255, 0, 0, 255)); + // Draw lane edges and vision/mpc tracks + ui_draw_vision_lanes(s); + } + + if (scene->lead_status) { + // Draw lead car indicator + float fillAlpha = 0; + float speedBuff = 10.; + float leadBuff = 40.; + if (scene->lead_d_rel < leadBuff) { + fillAlpha = 255*(1.0-(scene->lead_d_rel/leadBuff)); + if (scene->lead_v_rel < 0) { + fillAlpha += 255*(-1*(scene->lead_v_rel/speedBuff)); + } + fillAlpha = (int)(min(fillAlpha, 255)); } + draw_chevron(s, scene->lead_d_rel+2.7, scene->lead_y_rel, 25, + nvgRGBA(201, 34, 49, fillAlpha), nvgRGBA(218, 202, 37, 255)); } } -static void ui_draw_vision(UIState *s) { +static void ui_draw_vision_maxspeed(UIState *s) { const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + float maxspeed = s->scene.v_cruise; - glClearColor(0.0, 0.0, 0.0, 0.0); - glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); - - // hack for eon ui - glEnable(GL_SCISSOR_TEST); - glScissor(box_x, s->fb_h-(box_y+box_height), box_width, box_height); - glViewport(box_x, s->fb_h-(box_y+box_height), box_width, box_height); - draw_frame(s); - glViewport(0, 0, s->fb_w, s->fb_h); - glDisable(GL_SCISSOR_TEST); - - // nvg drawings - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - // glEnable(GL_CULL_FACE); - - glClear(GL_STENCIL_BUFFER_BIT); - - nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); - - nvgSave(s->vg); + const int viz_maxspeed_x = (ui_viz_rx + (bdr_s*2)); + const int viz_maxspeed_y = (box_y + (bdr_s*1.5)); + const int viz_maxspeed_w = 180; + const int viz_maxspeed_h = 202; + char maxspeed_str[32]; + bool is_cruise_set = (maxspeed != 0 && maxspeed != 255); - // hack for eon ui - const int inner_height = box_width*9/16; - nvgScissor(s->vg, box_x, box_y, box_width, box_height); - nvgTranslate(s->vg, box_x, box_y + (box_height-inner_height)/2.0); - nvgScale(s->vg, (float)box_width / s->fb_w, (float)inner_height / s->fb_h); + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, 20); + nvgStrokeColor(s->vg, nvgRGBA(255,255,255,80)); + nvgStrokeWidth(s->vg, 6); + nvgStroke(s->vg); - if (!scene->frontview) { - // ui_draw_transformed_box(s, 0xFF00FF00); - ui_draw_world(s); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, 26*2.5); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 200)); + nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, 148, "MAX", NULL); - if (scene->lead_status) { - draw_cross(s, scene->lead_d_rel + 2.7, scene->lead_y_rel, 30, - nvgRGBA(255, 0, 0, 128)); + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, 52*2.5); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + if (is_cruise_set) { + if (s->is_metric) { + snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(maxspeed + 0.5)); + } else { + snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(maxspeed * 0.6225 + 0.5)); } + nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, 242, maxspeed_str, NULL); + } else { + nvgFontSize(s->vg, 42*2.5); + nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, 242, "N/A", NULL); + } +} - const float label_size = 65.0f; - - nvgFontFace(s->vg, "courbd"); - - if (scene->awareness_status > 0) { - nvgBeginPath(s->vg); - int bar_height = scene->awareness_status * 700; - nvgRect(s->vg, 100, 300 + (700 - bar_height), 50, bar_height); - nvgFillColor(s->vg, nvgRGBA(255 * (1 - scene->awareness_status), - 255 * scene->awareness_status, 0, 128)); - nvgFill(s->vg); - } +static void ui_draw_vision_speedlimit(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; - // Draw calibration progress (if needed) - if (scene->cal_status == CALIBRATION_UNCALIBRATED) { - int rec_width = 1120; - int x_pos = 500; - nvgBeginPath(s->vg); - nvgStrokeWidth(s->vg, 14); - nvgRoundedRect(s->vg, (1920-rec_width)/2, 920, rec_width, 225, 20); - nvgStroke(s->vg); - nvgFillColor(s->vg, nvgRGBA(0,0,0,180)); - nvgFill(s->vg); - - nvgFontSize(s->vg, 40*2.5); - nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE); - nvgFontFace(s->vg, "sans-semibold"); - nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 220)); - char calib_status_str[64]; - snprintf(calib_status_str, sizeof(calib_status_str), "Calibration in Progress: %d%%", scene->cal_perc); - - nvgText(s->vg, x_pos, 1010, calib_status_str, NULL); - if (s->is_metric) { - nvgText(s->vg, x_pos + 120, 1110, "Drive above 72 km/h", NULL); - } else { - nvgText(s->vg, x_pos + 120, 1110, "Drive above 45 mph", NULL); - } - } + if (!s->scene.speedlimit_valid){ + return; } - nvgRestore(s->vg); + float speedlimit = s->scene.speedlimit; + const int viz_maxspeed_w = 180; + const int viz_maxspeed_h = 202; - if (!ui_alert_active(s) && !scene->frontview) { - // draw top bar + const int viz_event_w = 220; + const int viz_event_x = ((ui_viz_rx + ui_viz_rw) - (viz_event_w + (bdr_s*2))); - const int bar_x = box_x; - const int bar_y = box_y; - const int bar_width = box_width; - const int bar_height = 250 - box_y; + const int viz_maxspeed_x = viz_event_x + (viz_event_w-viz_maxspeed_w); + const int viz_maxspeed_y = (footer_y + ((footer_h - viz_maxspeed_h) / 2)) - 20; - assert(s->status < ARRAYSIZE(bg_colors)); - const uint8_t *color = bg_colors[s->status]; + char maxspeed_str[32]; + if (s->is_metric) { nvgBeginPath(s->vg); - nvgRect(s->vg, bar_x, bar_y, bar_width, bar_height); - nvgFillColor(s->vg, nvgRGBA(color[0], color[1], color[2], color[3])); + nvgCircle(s->vg, viz_maxspeed_x + viz_maxspeed_w / 2, viz_maxspeed_y + viz_maxspeed_h / 2, 127); + nvgFillColor(s->vg, nvgRGBA(195, 0, 0, 255)); nvgFill(s->vg); - const int message_y = box_y; - const int message_height = bar_height; - const int message_width = 800; - const int message_x = box_x + box_width / 2 - message_width / 2; - - // message background nvgBeginPath(s->vg); - NVGpaint bg = nvgLinearGradient(s->vg, message_x, message_y, message_x, message_y+message_height, - nvgRGBAf(0.0, 0.0, 0.0, 0.0), nvgRGBAf(0.0, 0.0, 0.0, 0.1)); - nvgFillPaint(s->vg, bg); - nvgRect(s->vg, message_x, message_y, message_width, message_height); + nvgCircle(s->vg, viz_maxspeed_x + viz_maxspeed_w / 2, viz_maxspeed_y + viz_maxspeed_h / 2, 100); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); nvgFill(s->vg); - nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 130); + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); - if (s->passive) { - if (s->scene.started_ts > 0) { - // draw drive time when passive + snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(speedlimit * 3.6 + 0.5)); + nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 135, maxspeed_str, NULL); + } else { + const int border = 10; + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, viz_maxspeed_x - border, viz_maxspeed_y - border, viz_maxspeed_w + 2 * border, viz_maxspeed_h + 2 * border, 30); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgFill(s->vg); - uint64_t dt = nanos_since_boot() - s->scene.started_ts; + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, 20); + nvgStrokeColor(s->vg, nvgRGBA(0, 0, 0, 255)); + nvgStrokeWidth(s->vg, 8); + nvgStroke(s->vg); - nvgFontFace(s->vg, "sans-semibold"); - nvgFontSize(s->vg, 40*2.5); - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); - char time_str[64]; - if (dt > 60*60*1000000000ULL) { - // hours - snprintf(time_str, sizeof(time_str), "Drive time: %d:%02d:%02d", - (int)(dt/(60*60*1000000000ULL)), - (int)((dt%(60*60*1000000000ULL))/(60*1000000000ULL)), - (int)(dt%(60*1000000000ULL)/1000000000ULL)); - } else { - snprintf(time_str, sizeof(time_str), "Drive time: %d:%02d", - (int)(dt/(60*1000000000ULL)), - (int)(dt%(60*1000000000ULL)/1000000000ULL)); - } - nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, time_str, NULL); - } - } else { - // status text - nvgFontFace(s->vg, "sans-semibold"); - nvgFontSize(s->vg, 48*2.5); - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); - if (s->scene.alert_size == cereal_Live100Data_AlertSize_small) { - nvgFontSize(s->vg, 40*2.5); - nvgText(s->vg, message_x+message_width/2, 115, s->scene.alert_text1, NULL); - nvgFontSize(s->vg, 26*2.5); - nvgText(s->vg, message_x+message_width/2, 185, s->scene.alert_text2, NULL); - } else if (s->status == STATUS_DISENGAGED) { - nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, "DISENGAGED", NULL); - } else if (s->status == STATUS_ENGAGED) { - nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, "ENGAGED", NULL); - } - } + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, 50); + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); + nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 50, "SPEED", NULL); + nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 90, "LIMIT", NULL); + + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 120); + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); + + snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(speedlimit * 2.2369363 + 0.5)); + nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 170, maxspeed_str, NULL); + } +} - // set speed - const int left_x = bar_x; - const int left_y = bar_y; - const int left_width = (bar_width - message_width) / 2; - const int left_height = bar_height; +static void ui_draw_vision_speed(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + float speed = s->scene.v_ego; - nvgFontFace(s->vg, "sans-semibold"); - nvgFontSize(s->vg, 40*2.5); - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + const int viz_speed_w = 280; + const int viz_speed_x = ui_viz_rx+((ui_viz_rw/2)-(viz_speed_w/2)); + char speed_str[32]; - if (scene->v_cruise != 255 && scene->v_cruise != 0) { - char speed_str[16]; - if (s->is_metric) { - snprintf(speed_str, sizeof(speed_str), "%3d kph", - (int)(scene->v_cruise + 0.5)); - } else { - /* Convert KPH to MPH. Using an approximated mph to kph - conversion factor of 1.609 because this is what the Honda - hud seems to be using */ - snprintf(speed_str, sizeof(speed_str), "%3d mph", - (int)(scene->v_cruise * 0.621504 + 0.5)); - } - nvgText(s->vg, left_x+left_width/2, 115, speed_str, NULL); - } else { - nvgText(s->vg, left_x+left_width/2, 115, "N/A", NULL); - } + nvgBeginPath(s->vg); + nvgRect(s->vg, viz_speed_x, box_y, viz_speed_w, header_h); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); - nvgFontFace(s->vg, "sans-regular"); - nvgFontSize(s->vg, 26*2.5); - nvgText(s->vg, left_x+left_width/2, 185, "SET SPEED", NULL); + if (s->is_metric) { + snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 3.6 + 0.5)); + } else { + snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 2.2369363 + 0.5)); + } + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 96*2.5); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgText(s->vg, viz_speed_x+viz_speed_w/2, 240, speed_str, NULL); - // lead car - const int right_y = bar_y; - const int right_width = (bar_width - message_width) / 2; - const int right_x = bar_x+bar_width-right_width; - const int right_height = bar_height; + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, 36*2.5); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 200)); - nvgFontFace(s->vg, "sans-semibold"); - nvgFontSize(s->vg, 40*2.5); - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + if (s->is_metric) { + nvgText(s->vg, viz_speed_x+viz_speed_w/2, 320, "kph", NULL); + } else { + nvgText(s->vg, viz_speed_x+viz_speed_w/2, 320, "mph", NULL); + } +} - if (scene->lead_status) { - char radar_str[16]; - // lead car is always in meters - if (s->is_metric || true) { - snprintf(radar_str, sizeof(radar_str), "%d m", (int)scene->lead_d_rel); - } else { - snprintf(radar_str, sizeof(radar_str), "%d ft", (int)(scene->lead_d_rel * 3.28084)); - } - nvgText(s->vg, right_x+right_width/2, 115, radar_str, NULL); - } else { - nvgText(s->vg, right_x+right_width/2, 115, "N/A", NULL); +static void ui_draw_vision_wheel(UIState *s) { + const UIScene *scene = &s->scene; + const int ui_viz_rx = scene->ui_viz_rx; + const int ui_viz_rw = scene->ui_viz_rw; + const int viz_event_w = 220; + const int viz_event_x = ((ui_viz_rx + ui_viz_rw) - (viz_event_w + (bdr_s*2))); + const int viz_event_y = (box_y + (bdr_s*1.5)); + const int viz_event_h = (header_h - (bdr_s*1.5)); + // draw steering wheel + const int bg_wheel_size = 96; + const int bg_wheel_x = viz_event_x + (viz_event_w-bg_wheel_size); + const int bg_wheel_y = viz_event_y + (bg_wheel_size/2); + const int img_wheel_size = bg_wheel_size*1.5; + const int img_wheel_x = bg_wheel_x-(img_wheel_size/2); + const int img_wheel_y = bg_wheel_y-25; + float img_wheel_alpha = 0.1f; + bool is_engaged = (s->status == STATUS_ENGAGED); + bool is_warning = (s->status == STATUS_WARNING); + bool is_engageable = scene->engageable; + if (is_engaged || is_warning || is_engageable) { + nvgBeginPath(s->vg); + nvgCircle(s->vg, bg_wheel_x, (bg_wheel_y + (bdr_s*1.5)), bg_wheel_size); + if (is_engaged) { + nvgFillColor(s->vg, nvgRGBA(23, 134, 68, 255)); + } else if (is_warning) { + nvgFillColor(s->vg, nvgRGBA(218, 111, 37, 255)); + } else if (is_engageable) { + nvgFillColor(s->vg, nvgRGBA(23, 51, 73, 255)); } - - nvgFontFace(s->vg, "sans-regular"); - nvgFontSize(s->vg, 26*2.5); - nvgText(s->vg, right_x+right_width/2, 185, "LEAD CAR", NULL); + nvgFill(s->vg); + img_wheel_alpha = 1.0f; } + nvgBeginPath(s->vg); + NVGpaint imgPaint = nvgImagePattern(s->vg, img_wheel_x, img_wheel_y, + img_wheel_size, img_wheel_size, 0, s->img_wheel, img_wheel_alpha); + nvgRect(s->vg, img_wheel_x, img_wheel_y, img_wheel_size, img_wheel_size); + nvgFillPaint(s->vg, imgPaint); + nvgFill(s->vg); +} - nvgEndFrame(s->vg); +static void ui_draw_vision_face(UIState *s) { + const UIScene *scene = &s->scene; + const int face_size = 96; + const int face_x = (scene->ui_viz_rx + face_size + (bdr_s * 2)); + const int face_y = (footer_y + ((footer_h - face_size) / 2)); + const int face_img_size = (face_size * 1.5); + const int face_img_x = (face_x - (face_img_size / 2)); + const int face_img_y = (face_y - (face_size / 4)); + float face_img_alpha = scene->monitoring_active ? 1.0f : 0.15f; + float face_bg_alpha = scene->monitoring_active ? 0.3f : 0.1f; + NVGcolor face_bg = nvgRGBA(0, 0, 0, (255 * face_bg_alpha)); + NVGpaint face_img = nvgImagePattern(s->vg, face_img_x, face_img_y, + face_img_size, face_img_size, 0, s->img_face, face_img_alpha); - glDisable(GL_BLEND); - // glDisable(GL_CULL_FACE); + nvgBeginPath(s->vg); + nvgCircle(s->vg, face_x, (face_y + (bdr_s * 1.5)), face_size); + nvgFillColor(s->vg, face_bg); + nvgFill(s->vg); + + nvgBeginPath(s->vg); + nvgRect(s->vg, face_img_x, face_img_y, face_img_size, face_img_size); + nvgFillPaint(s->vg, face_img); + nvgFill(s->vg); } -static void ui_draw_alerts(UIState *s) { +static void ui_draw_vision_header(UIState *s) { const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; - if (!ui_alert_active(s)) return; + nvgBeginPath(s->vg); + NVGpaint gradient = nvgLinearGradient(s->vg, ui_viz_rx, + (box_y+(header_h-(header_h/2.5))), + ui_viz_rx, box_y+header_h, + nvgRGBAf(0,0,0,0.45), nvgRGBAf(0,0,0,0)); + nvgFillPaint(s->vg, gradient); + nvgRect(s->vg, ui_viz_rx, box_y, ui_viz_rw, header_h); + nvgFill(s->vg); - assert(s->status < ARRAYSIZE(alert_colors)); - const uint8_t *color = alert_colors[s->status]; + ui_draw_vision_maxspeed(s); + ui_draw_vision_speed(s); + ui_draw_vision_wheel(s); +} - char alert_text1_upper[1024] = {0}; - for (int i=0; scene->alert_text1[i] && i < sizeof(alert_text1_upper)-1; i++) { - alert_text1_upper[i] = toupper(scene->alert_text1[i]); - } +static void ui_draw_vision_footer(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; nvgBeginPath(s->vg); - nvgRect(s->vg, box_x, box_y, box_width, box_height); - nvgFillColor(s->vg, nvgRGBA(color[0], color[1], color[2], color[3])); - nvgFill(s->vg); + nvgRect(s->vg, ui_viz_rx, footer_y, ui_viz_rw, footer_h); - nvgFontFace(s->vg, "sans-semibold"); + // Driver Monitoring + ui_draw_vision_face(s); - if (strlen(alert_text1_upper) > 15) { - nvgFontSize(s->vg, 72.0*2.5); - } else { - nvgFontSize(s->vg, 96.0*2.5); - } - nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE); - nvgTextBox(s->vg, box_x + 50, box_y + 287, box_width - 50, alert_text1_upper, NULL); + ui_draw_vision_speedlimit(s); +} +static void ui_draw_vision_alert(UIState *s, int va_size, int va_color, + const char* va_text1, const char* va_text2) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; + bool mapEnabled = s->scene.uilayout_mapenabled; + bool longAlert1 = strlen(va_text1) > 15; + + const uint8_t *color = alert_colors[va_color]; + const int alr_s = alert_sizes[va_size]; + const int alr_x = ui_viz_rx-(mapEnabled?(hasSidebar?nav_w:(nav_ww)):0)-bdr_s; + const int alr_w = ui_viz_rw+(mapEnabled?(hasSidebar?nav_w:(nav_ww)):0)+(bdr_s*2); + const int alr_h = alr_s+(va_size==ALERTSIZE_NONE?0:bdr_s); + const int alr_y = vwp_h-alr_h; - if (strlen(scene->alert_text2) > 0) { + nvgBeginPath(s->vg); + nvgRect(s->vg, alr_x, alr_y, alr_w, alr_h); + nvgFillColor(s->vg, nvgRGBA(color[0],color[1],color[2],(color[3]*s->alert_blinking_alpha))); + nvgFill(s->vg); + + nvgBeginPath(s->vg); + NVGpaint gradient = nvgLinearGradient(s->vg, alr_x, alr_y, alr_x, alr_y+alr_h, + nvgRGBAf(0.0,0.0,0.0,0.05), nvgRGBAf(0.0,0.0,0.0,0.35)); + nvgFillPaint(s->vg, gradient); + nvgRect(s->vg, alr_x, alr_y, alr_w, alr_h); + nvgFill(s->vg); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + + if (va_size == ALERTSIZE_SMALL) { + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, 40*2.5); + nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+15, va_text1, NULL); + } else if (va_size== ALERTSIZE_MID) { + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 48*2.5); + nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2-45, va_text1, NULL); + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, 36*2.5); + nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+75, va_text2, NULL); + } else if (va_size== ALERTSIZE_FULL) { + nvgFontSize(s->vg, (longAlert1?72:96)*2.5); + nvgFontFace(s->vg, "sans-bold"); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE); + nvgTextBox(s->vg, alr_x, alr_y+(longAlert1?360:420), alr_w-60, va_text1, NULL); + nvgFontSize(s->vg, 48*2.5); nvgFontFace(s->vg, "sans-regular"); - nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); - nvgFontSize(s->vg, 44.0*2.5); nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BOTTOM); - nvgTextBox(s->vg, box_x + 50, box_y + box_height - 250, box_width - 50, scene->alert_text2, NULL); + nvgTextBox(s->vg, alr_x, alr_h-(longAlert1?300:360), alr_w-60, va_text2, NULL); } } -static void ui_draw_blank(UIState *s) { +static void ui_draw_vision(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + int ui_viz_ro = scene->ui_viz_ro; + glClearColor(0.0, 0.0, 0.0, 0.0); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); -} -static void ui_draw_aside(UIState *s) { - char speed_str[32]; - float speed; - - bool is_cruise_set = (s->scene.v_cruise != 0 && s->scene.v_cruise != 255); - unsigned long last_cruise_update_dt = (nanos_since_boot() - s->scene.v_cruise_update_ts); - bool should_draw_cruise_speed = is_cruise_set && last_cruise_update_dt < 2000000000ULL; - if (should_draw_cruise_speed) { - speed = s->scene.v_cruise / 3.6; - nvgFillColor(s->vg, nvgRGBA(0xFF, 0xD8, 0xAC, 0xFF)); - } else { - speed = s->scene.v_ego; - nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); - } + // Draw video frames + glEnable(GL_SCISSOR_TEST); + glViewport(ui_viz_rx+ui_viz_ro, s->fb_h-(box_y+box_h), viz_w, box_h); + glScissor(ui_viz_rx, s->fb_h-(box_y+box_h), ui_viz_rw, box_h); + draw_frame(s); + glViewport(0, 0, s->fb_w, s->fb_h); + glDisable(GL_SCISSOR_TEST); - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glClear(GL_STENCIL_BUFFER_BIT); - nvgFontFace(s->vg, "sans-semibold"); - nvgFontSize(s->vg, 110); - if (s->is_metric) { - snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 3.6 + 0.5)); - } else { - snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 2.2374144 + 0.5)); + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); + nvgSave(s->vg); + + // Draw augmented elements + const int inner_height = viz_w*9/16; + nvgScissor(s->vg, ui_viz_rx, box_y, ui_viz_rw, box_h); + nvgTranslate(s->vg, ui_viz_rx+ui_viz_ro, box_y + (box_h-inner_height)/2.0); + nvgScale(s->vg, (float)viz_w / s->fb_w, (float)inner_height / s->fb_h); + if (!scene->frontview && !scene->fullview) { + ui_draw_world(s); } - nvgText(s->vg, 150, 762, speed_str, NULL); - nvgFontFace(s->vg, "sans-regular"); - nvgFontSize(s->vg, 70); + nvgRestore(s->vg); - if (s->is_metric) { - nvgText(s->vg, 150, 817, "kph", NULL); + // Set Speed, Current Speed, Status/Events + ui_draw_vision_header(s); + + if (s->scene.alert_size != ALERTSIZE_NONE) { + // Controls Alerts + ui_draw_vision_alert(s, s->scene.alert_size, s->status, + s->scene.alert_text1, s->scene.alert_text2); } else { - nvgText(s->vg, 150, 817, "mph", NULL); + ui_draw_vision_footer(s); } + + + nvgEndFrame(s->vg); + glDisable(GL_BLEND); +} + +static void ui_draw_blank(UIState *s) { + glClearColor(0.0, 0.0, 0.0, 0.0); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); } static void ui_draw(UIState *s) { @@ -1117,16 +1279,10 @@ static void ui_draw(UIState *s) { nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); - if (s->vision_connected) { - ui_draw_aside(s); - } - ui_draw_alerts(s); - nvgEndFrame(s->vg); glDisable(GL_BLEND); } - eglSwapBuffers(s->display, s->surface); assert(glGetError() == GL_NO_ERROR); } @@ -1178,48 +1334,74 @@ static void update_status(UIState *s, int status) { static void ui_update(UIState *s) { int err; - if (!s->intrinsic_matrix_loaded) { - s->intrinsic_matrix_loaded = try_load_intrinsics(&s->intrinsic_matrix); - } - if (s->vision_connect_firstrun) { // cant run this in connector thread because opengl. // do this here for now in lieu of a run_on_main_thread event - // setup frame texture - glDeleteTextures(1, &s->frame_tex); //silently ignores a 0 texture - glGenTextures(1, &s->frame_tex); - glBindTexture(GL_TEXTURE_2D, s->frame_tex); - glTexStorage2D(GL_TEXTURE_2D, 1, GL_RGB8, s->rgb_width, s->rgb_height); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - - // BGR - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); - - // front - glDeleteTextures(1, &s->frame_front_tex); - glGenTextures(1, &s->frame_front_tex); - glBindTexture(GL_TEXTURE_2D, s->frame_front_tex); - glTexStorage2D(GL_TEXTURE_2D, 1, GL_RGB8, s->rgb_front_width, s->rgb_front_height); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - - // BGR - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + for (int i=0; iframe_texs[i]); + + VisionImg img = { + .fd = s->bufs[i].fd, + .format = VISIONIMG_FORMAT_RGB24, + .width = s->rgb_width, + .height = s->rgb_height, + .stride = s->rgb_stride, + .bpp = 3, + .size = s->rgb_buf_len, + }; + s->frame_texs[i] = visionimg_to_gl(&img); + + glBindTexture(GL_TEXTURE_2D, s->frame_texs[i]); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + } + + for (int i=0; iframe_front_texs[i]); + + VisionImg img = { + .fd = s->front_bufs[i].fd, + .format = VISIONIMG_FORMAT_RGB24, + .width = s->rgb_front_width, + .height = s->rgb_front_height, + .stride = s->rgb_front_stride, + .bpp = 3, + .size = s->rgb_front_buf_len, + }; + s->frame_front_texs[i] = visionimg_to_gl(&img); + + glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[i]); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + } assert(glGetError() == GL_NO_ERROR); + // Default UI Measurements (Assumes sidebar collapsed) + s->scene.ui_viz_rx = (box_x-sbr_w+bdr_s*2); + s->scene.ui_viz_rw = (box_w+sbr_w-(bdr_s*2)); + s->scene.ui_viz_ro = 0; + s->vision_connect_firstrun = false; + + s->alert_blinking_alpha = 1.0; + s->alert_blinked = false; } // poll for events while (true) { - zmq_pollitem_t polls[8] = {{0}}; + zmq_pollitem_t polls[10] = {{0}}; polls[0].socket = s->live100_sock_raw; polls[0].events = ZMQ_POLLIN; polls[1].socket = s->livecalibration_sock_raw; @@ -1232,15 +1414,18 @@ static void ui_update(UIState *s) { polls[4].events = ZMQ_POLLIN; polls[5].socket = s->thermal_sock_raw; polls[5].events = ZMQ_POLLIN; - - polls[6].socket = s->plus_sock_raw; + polls[6].socket = s->uilayout_sock_raw; polls[6].events = ZMQ_POLLIN; + polls[7].socket = s->map_data_sock_raw; + polls[7].events = ZMQ_POLLIN; + polls[8].socket = s->plus_sock_raw; // plus_sock should be last + polls[8].events = ZMQ_POLLIN; - int num_polls = 7; + int num_polls = 9; if (s->vision_connected) { assert(s->ipc_fd >= 0); - polls[7].fd = s->ipc_fd; - polls[7].events = ZMQ_POLLIN; + polls[9].fd = s->ipc_fd; + polls[9].events = ZMQ_POLLIN; num_polls++; } @@ -1254,12 +1439,13 @@ static void ui_update(UIState *s) { } if (polls[0].revents || polls[1].revents || polls[2].revents || - polls[3].revents || polls[4].revents) { + polls[3].revents || polls[4].revents || polls[6].revents || + polls[7].revents || polls[8].revents) { // awake on any (old) activity set_awake(s, true); } - if (s->vision_connected && polls[7].revents) { + if (s->vision_connected && polls[9].revents) { // vision ipc event VisionPacket rp; err = vipc_recv(s->ipc_fd, &rp); @@ -1271,7 +1457,7 @@ static void ui_update(UIState *s) { continue; } if (rp.type == VIPC_STREAM_ACQUIRE) { - bool front = rp.d.stream_acq.type == VISION_STREAM_UI_FRONT; + bool front = rp.d.stream_acq.type == VISION_STREAM_RGB_FRONT; int idx = rp.d.stream_acq.idx; int release_idx; @@ -1294,21 +1480,15 @@ static void ui_update(UIState *s) { if (front) { assert(idx < UI_BUF_COUNT); s->cur_vision_front_idx = idx; - s->scene.bgr_front_ptr = s->front_bufs[idx].addr; } else { assert(idx < UI_BUF_COUNT); s->cur_vision_idx = idx; - s->scene.bgr_ptr = s->bufs[idx].addr; // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); } - if (front == s->scene.frontview) { - ui_update_frame(s); - } - } else { assert(false); } - } else if (polls[6].revents) { + } else if (polls[8].revents) { // plus socket zmq_msg_t msg; @@ -1326,7 +1506,7 @@ static void ui_update(UIState *s) { } else { // zmq messages void* which = NULL; - for (int i=0; i<6; i++) { + for (int i=0; iscene.v_ego = datad.vEgo; s->scene.curvature = datad.curvature; s->scene.engaged = datad.enabled; - // printf("recv %f\n", datad.vEgo); + s->scene.engageable = datad.engageable; + s->scene.gps_planner_active = datad.gpsPlannerActive; + s->scene.monitoring_active = datad.driverMonitoringOn; s->scene.frontview = datad.rearViewCam; + + if (datad.alertSound.str && datad.alertSound.str[0] != '\0' && strcmp(s->alert_type, datad.alertType.str) != 0) { + char* error = NULL; + if (s->alert_sound[0] != '\0') { + sound_file* active_sound = get_sound_file_by_name(s->alert_sound); + slplay_stop_uri(active_sound->uri, &error); + if (error) { + LOGW("error stopping active sound %s", error); + } + } + + sound_file* sound = get_sound_file_by_name(datad.alertSound.str); + slplay_play(sound->uri, sound->loop, &error); + if(error) { + LOGW("error playing sound: %s", error); + } + + snprintf(s->alert_sound, sizeof(s->alert_sound), "%s", datad.alertSound.str); + snprintf(s->alert_type, sizeof(s->alert_type), "%s", datad.alertType.str); + } else if ((!datad.alertSound.str || datad.alertSound.str[0] == '\0') && s->alert_sound[0] != '\0') { + sound_file* sound = get_sound_file_by_name(s->alert_sound); + + char* error = NULL; + + slplay_stop_uri(sound->uri, &error); + if(error) { + LOGW("error stopping sound: %s", error); + } + s->alert_type[0] = '\0'; + s->alert_sound[0] = '\0'; + } + if (datad.alertText1.str) { snprintf(s->scene.alert_text1, sizeof(s->scene.alert_text1), "%s", datad.alertText1.str); } else { @@ -1379,6 +1593,15 @@ static void ui_update(UIState *s) { s->scene.alert_ts = eventd.logMonoTime; s->scene.alert_size = datad.alertSize; + if (datad.alertSize == cereal_Live100Data_AlertSize_none) { + s->alert_size = ALERTSIZE_NONE; + } else if (datad.alertSize == cereal_Live100Data_AlertSize_small) { + s->alert_size = ALERTSIZE_SMALL; + } else if (datad.alertSize == cereal_Live100Data_AlertSize_mid) { + s->alert_size = ALERTSIZE_MID; + } else if (datad.alertSize == cereal_Live100Data_AlertSize_full) { + s->alert_size = ALERTSIZE_FULL; + } if (datad.alertStatus == cereal_Live100Data_AlertStatus_userPrompt) { update_status(s, STATUS_WARNING); @@ -1390,6 +1613,23 @@ static void ui_update(UIState *s) { update_status(s, STATUS_DISENGAGED); } + s->scene.alert_blinkingrate = datad.alertBlinkingRate; + if (datad.alertBlinkingRate > 0.) { + if (s->alert_blinked) { + if (s->alert_blinking_alpha > 0.0 && s->alert_blinking_alpha < 1.0) { + s->alert_blinking_alpha += (0.05*datad.alertBlinkingRate); + } else { + s->alert_blinked = false; + } + } else { + if (s->alert_blinking_alpha > 0.25) { + s->alert_blinking_alpha -= (0.05*datad.alertBlinkingRate); + } else { + s->alert_blinking_alpha += 0.25; + s->alert_blinked = true; + } + } + } } else if (eventd.which == cereal_Event_live20) { struct cereal_Live20Data datad; cereal_read_Live20Data(&datad, eventd.live20); @@ -1400,13 +1640,10 @@ static void ui_update(UIState *s) { s->scene.lead_y_rel = leaddatad.yRel; s->scene.lead_v_rel = leaddatad.vRel; } else if (eventd.which == cereal_Event_liveCalibration) { - s->scene.world_objects_visible = s->intrinsic_matrix_loaded; + s->scene.world_objects_visible = true; struct cereal_LiveCalibrationData datad; cereal_read_LiveCalibrationData(&datad, eventd.liveCalibration); - s->scene.cal_status = datad.calStatus; - s->scene.cal_perc = datad.calPerc; - // should we still even have this? capn_list32 warpl = datad.warpMatrix2; capn_resolve(&warpl.p); // is this a bug? @@ -1452,17 +1689,73 @@ static void ui_update(UIState *s) { } s->scene.started_ts = datad.startedTs; + } else if (eventd.which == cereal_Event_uiLayoutState) { + struct cereal_UiLayoutState datad; + cereal_read_UiLayoutState(&datad, eventd.uiLayoutState); + s->scene.uilayout_sidebarcollapsed = datad.sidebarCollapsed; + s->scene.uilayout_mapenabled = datad.mapEnabled; + + bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; + bool mapEnabled = s->scene.uilayout_mapenabled; + if (mapEnabled) { + s->scene.ui_viz_rx = hasSidebar ? (box_x+nav_w) : (box_x+nav_w-(bdr_s*4)); + s->scene.ui_viz_rw = hasSidebar ? (box_w-nav_w) : (box_w-nav_w+(bdr_s*4)); + s->scene.ui_viz_ro = -(sbr_w + 4*bdr_s); + } else { + s->scene.ui_viz_rx = hasSidebar ? box_x : (box_x-sbr_w+bdr_s*2); + s->scene.ui_viz_rw = hasSidebar ? box_w : (box_w+sbr_w-(bdr_s*2)); + s->scene.ui_viz_ro = hasSidebar ? -(sbr_w - 6*bdr_s) : 0; + } + } else if (eventd.which == cereal_Event_liveMapData) { + struct cereal_LiveMapData datad; + cereal_read_LiveMapData(&datad, eventd.liveMapData); + s->scene.speedlimit = datad.speedLimit; + s->scene.speedlimit_valid = datad.valid; } - capn_free(&ctx); - zmq_msg_close(&msg); - } } } +static int vision_subscribe(int fd, VisionPacket *rp, int type) { + int err; + LOGW("vision_subscribe type:%d", type); + + VisionPacket p1 = { + .type = VIPC_STREAM_SUBSCRIBE, + .d = { .stream_sub = { .type = type, .tbuffer = true, }, }, + }; + err = vipc_send(fd, &p1); + if (err < 0) { + close(fd); + return 0; + } + + do { + err = vipc_recv(fd, rp); + if (err <= 0) { + close(fd); + return 0; + } + + // release what we aren't ready for yet + if (rp->type == VIPC_STREAM_ACQUIRE) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = rp->d.stream_acq.type, + .idx = rp->d.stream_acq.idx, + }}, + }; + vipc_send(fd, &rep); + } + } while (rp->type != VIPC_STREAM_BUFS || rp->d.stream_bufs.type != type); + + return 1; +} + static void* vision_connect_thread(void *args) { int err; @@ -1477,43 +1770,9 @@ static void* vision_connect_thread(void *args) { int fd = vipc_connect(); if (fd < 0) continue; - - - VisionPacket p1 = { - .type = VIPC_STREAM_SUBSCRIBE, - .d = { .stream_sub = { .type = VISION_STREAM_UI_BACK, .tbuffer = true, }, }, - }; - err = vipc_send(fd, &p1); - if (err < 0) { - close(fd); - continue; - } - VisionPacket p2 = { - .type = VIPC_STREAM_SUBSCRIBE, - .d = { .stream_sub = { .type = VISION_STREAM_UI_FRONT, .tbuffer = true, }, }, - }; - err = vipc_send(fd, &p2); - if (err < 0) { - close(fd); - continue; - } - - // printf("init recv\n"); - VisionPacket back_rp; - err = vipc_recv(fd, &back_rp); - if (err <= 0) { - close(fd); - continue; - } - assert(back_rp.type == VIPC_STREAM_BUFS); - VisionPacket front_rp; - err = vipc_recv(fd, &front_rp); - if (err <= 0) { - close(fd); - continue; - } - assert(front_rp.type == VIPC_STREAM_BUFS); - + VisionPacket back_rp, front_rp; + if (!vision_subscribe(fd, &back_rp, VISION_STREAM_RGB_BACK)) continue; + if (!vision_subscribe(fd, &front_rp, VISION_STREAM_RGB_FRONT)) continue; pthread_mutex_lock(&s->lock); assert(!s->vision_connected); @@ -1530,11 +1789,10 @@ static void* vision_connect_thread(void *args) { return NULL; } + #include #include -#define SENSOR_LIGHT 7 - static void* light_sensor_thread(void *args) { int err; @@ -1551,6 +1809,8 @@ static void* light_sensor_thread(void *args) { struct sensor_t const* list; int count = module->get_sensors_list(module, &list); + int SENSOR_LIGHT = 7; + device->activate(device, SENSOR_LIGHT, 0); device->activate(device, SENSOR_LIGHT, 1); device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); @@ -1565,7 +1825,6 @@ static void* light_sensor_thread(void *args) { } if (n > 0) { s->light_sensor = buffer[0].light; - //printf("new light sensor value: %f\n", s->light_sensor); } } @@ -1583,36 +1842,48 @@ static void* bg_thread(void* args) { &bg_display, &bg_surface, NULL, NULL); assert(bg_fb); - bool first = true; + int bg_status = -1; while(!do_exit) { pthread_mutex_lock(&s->lock); - - if (first) { - first = false; - } else { + if (bg_status == s->status) { + // will always be signaled if it changes? pthread_cond_wait(&s->bg_cond, &s->lock); } - - assert(s->status < ARRAYSIZE(bg_colors)); - const uint8_t *color = bg_colors[s->status]; - + bg_status = s->status; pthread_mutex_unlock(&s->lock); + assert(bg_status < ARRAYSIZE(bg_colors)); + const uint8_t *color = bg_colors[bg_status]; + glClearColor(color[0]/256.0, color[1]/256.0, color[2]/256.0, 0.0); glClear(GL_COLOR_BUFFER_BIT); - eglSwapBuffers(bg_display, bg_surface); assert(glGetError() == GL_NO_ERROR); - } return NULL; } +int is_leon() { + #define MAXCHAR 1000 + FILE *fp; + char str[MAXCHAR]; + char* filename = "/proc/cmdline"; + + fp = fopen(filename, "r"); + if (fp == NULL){ + printf("Could not open file %s",filename); + return 0; + } + fgets(str, MAXCHAR, fp); + fclose(fp); + return strstr(str, "letv") != NULL; +} int main() { int err; + setpriority(PRIO_PROCESS, 0, -14); zsys_handler_set(NULL); signal(SIGINT, (sighandler_t)set_do_exit); @@ -1639,38 +1910,46 @@ int main() { TouchState touch = {0}; touch_init(&touch); + char* error = NULL; + ui_sound_init(&error); + if (error) { + LOGW(error); + exit(1); + } + // light sensor scaling params - #define LIGHT_SENSOR_M 1.3 - #define LIGHT_SENSOR_B 5.0 + const int EON = (access("/EON", F_OK) != -1); + const int LEON = is_leon(); + const float BRIGHTNESS_B = LEON? 10.0 : 5.0; + const float BRIGHTNESS_M = LEON? 2.6 : 1.3; #define NEO_BRIGHTNESS 100 - float smooth_light_sensor = LIGHT_SENSOR_B; + float smooth_brightness = BRIGHTNESS_B; - const int EON = (access("/EON", F_OK) != -1); + set_volume(s, 0); while (!do_exit) { + bool should_swap = false; pthread_mutex_lock(&s->lock); if (EON) { // light sensor is only exposed on EONs - float clipped_light_sensor = (s->light_sensor*LIGHT_SENSOR_M) + LIGHT_SENSOR_B; - if (clipped_light_sensor > 255) clipped_light_sensor = 255; - smooth_light_sensor = clipped_light_sensor * 0.01 + smooth_light_sensor * 0.99; - set_brightness((int)smooth_light_sensor); + + float clipped_brightness = (s->light_sensor*BRIGHTNESS_M) + BRIGHTNESS_B; + if (clipped_brightness > 255) clipped_brightness = 255; + smooth_brightness = clipped_brightness * 0.01 + smooth_brightness * 0.99; + set_brightness(s, (int)smooth_brightness); } else { // compromise for bright and dark envs - set_brightness(NEO_BRIGHTNESS); + set_brightness(s, NEO_BRIGHTNESS); } ui_update(s); - if (s->awake) { - ui_draw(s); - } // awake on any touch int touch_x = -1, touch_y = -1; - int touched = touch_poll(&touch, &touch_x, &touch_y); + int touched = touch_poll(&touch, &touch_x, &touch_y, s->awake ? 0 : 100); if (touched == 1) { // touch event will still happen :( set_awake(s, true); @@ -1683,14 +1962,32 @@ int main() { set_awake(s, false); } + if (s->awake) { + ui_draw(s); + glFinish(); + should_swap = true; + } + + if (s->volume_timeout > 0) { + s->volume_timeout--; + } else { + int volume = min(13, 11 + s->scene.v_ego / 15); // up one notch every 15 m/s, starting at 11 + set_volume(s, volume); + } + pthread_mutex_unlock(&s->lock); - // no simple way to do 30fps vsync with surfaceflinger... - usleep(30000); + // the bg thread needs to be scheduled, so the main thread needs time without the lock + // safe to do this outside the lock? + if (should_swap) { + eglSwapBuffers(s->display, s->surface); + } } set_awake(s, true); + slplay_destroy(); + // wake up bg thread to exit pthread_mutex_lock(&s->lock); pthread_cond_signal(&s->bg_cond); diff --git a/selfdrive/updated.py b/selfdrive/updated.py old mode 100644 new mode 100755 index b87b0a9162c76e..c8efd8f3a86bf7 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -1,11 +1,12 @@ #!/usr/bin/env python -# simple service that waits for network access and tries to update every 3 hours +# simple service that waits for network access and tries to update every hour -import os import time import subprocess +from selfdrive.swaglog import cloudlog +NICE_LOW_PRIORITY = ["nice", "-n", "19"] def main(gctx=None): while True: # try network @@ -14,13 +15,20 @@ def main(gctx=None): time.sleep(60) continue - # try fetch - r = subprocess.call(["nice", "-n", "19", "git", "fetch", "--depth=1"]) - if r: + # download application update + try: + r = subprocess.check_output(NICE_LOW_PRIORITY + ["git", "fetch"], stderr=subprocess.STDOUT) + except subprocess.CalledProcessError, e: + cloudlog.event("git fetch failed", + cmd=e.cmd, + output=e.output, + returncode=e.returncode) time.sleep(60) continue + cloudlog.info("git fetch success: %s", r) - time.sleep(60*60*3) + time.sleep(60*60) if __name__ == "__main__": - main() + main() + diff --git a/selfdrive/version.py b/selfdrive/version.py index b5d667f39a9fb4..8166c662f40dbf 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -1,3 +1,21 @@ import os +import subprocess with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: version = _versionf.read().split('"')[1] + +try: + origin = subprocess.check_output(["git", "config", "--get", "remote.origin.url"]).rstrip() + if origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai'): + if origin.endswith('/one.git'): + dirty = True + else: + branch = subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]).rstrip() + branch = 'origin/' + branch + dirty = subprocess.call(["git", "diff-index", "--quiet", branch, "--"]) != 0 + else: + dirty = True +except subprocess.CalledProcessError: + dirty = True + +# put this here +training_version = "0.1.0" diff --git a/selfdrive/visiond/README b/selfdrive/visiond/README index ae92bd4b3f1605..d237562739bcd0 100644 --- a/selfdrive/visiond/README +++ b/selfdrive/visiond/README @@ -1,3 +1,3 @@ -visiond runs the openpilot vision pipeline. Everything running between the camera hardware and model outputs lives here. +visiond runs the openpilot/chffrplus vision pipeline. Everything running between the camera hardware and model outputs lives here. Contact us if you'd like features added or support for your platform. diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond index 1a1b65f2119c93..40259afc55c789 100755 Binary files a/selfdrive/visiond/visiond and b/selfdrive/visiond/visiond differ